mirror of
https://bitbucket.org/librepilot/librepilot.git
synced 2024-12-01 09:24:10 +01:00
Merge remote-tracking branch 'origin/brian/rfm22_autoconf' into next
Conflicts: ground/openpilotgcs/src/plugins/config/configgadgetwidget.cpp
This commit is contained in:
commit
a4faa22c4b
@ -32,6 +32,8 @@
|
||||
|
||||
#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)
|
||||
@ -40,19 +42,14 @@
|
||||
// Public types
|
||||
typedef enum {
|
||||
PACKET_TYPE_NONE = 0,
|
||||
PACKET_TYPE_CONNECT, // for requesting a connection
|
||||
PACKET_TYPE_DISCONNECT, // to tell the other modem they cannot connect to us
|
||||
PACKET_TYPE_READY, // tells the other modem we are ready to accept more data
|
||||
PACKET_TYPE_NOTREADY, // tells the other modem we're not ready to accept more data - we can also send user data in this packet type
|
||||
PACKET_TYPE_STATUS, // broadcasts status of this modem
|
||||
PACKET_TYPE_DATARATE, // for changing the RF data rate
|
||||
PACKET_TYPE_PING, // used to check link is still up
|
||||
PACKET_TYPE_ADJUST_TX_PWR, // used to ask the other modem to adjust it's tx power
|
||||
PACKET_TYPE_CON_REQUEST, // request a connection to another modem
|
||||
PACKET_TYPE_DATA, // data packet (packet contains user data)
|
||||
PACKET_TYPE_ACKED_DATA, // data packet that requies an ACK
|
||||
PACKET_TYPE_DUPLICATE_DATA, // a duplicate data packet
|
||||
PACKET_TYPE_PPM, // PPM relay values
|
||||
PACKET_TYPE_ACK,
|
||||
PACKET_TYPE_NACK
|
||||
PACKET_TYPE_ACK, // Acknowlege the receipt of a packet
|
||||
PACKET_TYPE_ACK_RTS, // Acknowlege the receipt of a packet and indicate that the receiving side has data to send (ready to send)
|
||||
PACKET_TYPE_NACK, // Acknowlege the receipt of an uncorrectable packet
|
||||
} PHPacketType;
|
||||
|
||||
typedef struct {
|
||||
@ -64,58 +61,45 @@ typedef struct {
|
||||
} 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)
|
||||
#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;
|
||||
uint16_t channels[GCSRECEIVER_CHANNEL_NUMELEM];
|
||||
uint16_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;
|
||||
uint16_t retries;
|
||||
uint16_t errors;
|
||||
uint16_t uavtalk_errors;
|
||||
uint16_t dropped;
|
||||
uint16_t resets;
|
||||
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 {
|
||||
uint32_t default_destination_id;
|
||||
uint32_t source_id;
|
||||
uint16_t max_connections;
|
||||
uint8_t win_size;
|
||||
} PacketHandlerConfig;
|
||||
|
||||
typedef int32_t (*PHOutputStream)(PHPacketHandle packet);
|
||||
typedef void (*PHDataHandler)(uint8_t *data, uint8_t len, int8_t rssi, int8_t afc);
|
||||
typedef void (*PHStatusHandler)(PHStatusPacketHandle s, int8_t rssi, int8_t afc);
|
||||
typedef void (*PHPPMHandler)(uint16_t *channels);
|
||||
|
||||
typedef uint32_t PHInstHandle;
|
||||
|
||||
// Public functions
|
||||
PHInstHandle PHInitialize(PacketHandlerConfig *cfg);
|
||||
void PHRegisterOutputStream(PHInstHandle h, PHOutputStream f);
|
||||
void PHRegisterDataHandler(PHInstHandle h, PHDataHandler f);
|
||||
void PHRegisterStatusHandler(PHInstHandle h, PHStatusHandler f);
|
||||
void PHRegisterPPMHandler(PHInstHandle h, PHPPMHandler f);
|
||||
uint32_t PHConnect(PHInstHandle h, uint32_t dest_id);
|
||||
PHPacketHandle PHGetRXPacket(PHInstHandle h);
|
||||
void PHReleaseRXPacket(PHInstHandle h, PHPacketHandle p);
|
||||
PHPacketHandle PHGetTXPacket(PHInstHandle h);
|
||||
void PHReleaseTXPacket(PHInstHandle h, PHPacketHandle p);
|
||||
uint8_t PHTransmitPacket(PHInstHandle h, PHPacketHandle p);
|
||||
uint8_t PHTransmitData(PHInstHandle h, uint8_t *buf, uint16_t len);
|
||||
uint8_t PHReceivePacket(PHInstHandle h, PHPacketHandle p);
|
||||
PHPacketHeader header;
|
||||
uint8_t datarate;
|
||||
uint32_t frequency_hz;
|
||||
uint32_t min_frequency;
|
||||
uint32_t max_frequency;
|
||||
uint8_t max_tx_power;
|
||||
OPLinkSettingsOutputConnectionOptions port;
|
||||
OPLinkSettingsComSpeedOptions com_speed;
|
||||
uint8_t ecc[RS_ECC_NPARITY];
|
||||
} PHConnectionPacket, *PHConnectionPacketHandle;
|
||||
|
||||
#endif // __PACKET_HANDLER_H__
|
||||
|
||||
|
@ -1,385 +0,0 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup OpenPilotSystem OpenPilot System
|
||||
* @{
|
||||
* @addtogroup OpenPilotLibraries OpenPilot System Libraries
|
||||
* @{
|
||||
*
|
||||
* @file packet_handler.c
|
||||
* @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
|
||||
*/
|
||||
|
||||
#include "openpilot.h"
|
||||
#include "packet_handler.h"
|
||||
#include "aes.h"
|
||||
#include "ecc.h"
|
||||
|
||||
extern char *debug_msg;
|
||||
|
||||
// Private types and constants
|
||||
typedef struct {
|
||||
PacketHandlerConfig cfg;
|
||||
PHPacket *tx_packets;
|
||||
uint8_t tx_win_start;
|
||||
uint8_t tx_win_end;
|
||||
PHPacket *rx_packets;
|
||||
uint8_t rx_win_start;
|
||||
uint8_t rx_win_end;
|
||||
xSemaphoreHandle lock;
|
||||
PHOutputStream output_stream;
|
||||
PHDataHandler data_handler;
|
||||
PHStatusHandler status_handler;
|
||||
PHPPMHandler ppm_handler;
|
||||
} PHPacketData, *PHPacketDataHandle;
|
||||
|
||||
// Private functions
|
||||
static uint8_t PHLTransmitPacket(PHPacketDataHandle data, PHPacketHandle p);
|
||||
|
||||
/**
|
||||
* Initialize the Packet Handler library
|
||||
* \param[in] txWinSize The transmission window size (number of tx packet buffers).
|
||||
* \param[in] streme A callback function for transmitting the packet.
|
||||
* \param[in] id The source ID of transmitter.
|
||||
* \return PHInstHandle The Pachet Handler instance data.
|
||||
* \return 0 Failure
|
||||
*/
|
||||
PHInstHandle PHInitialize(PacketHandlerConfig *cfg)
|
||||
{
|
||||
// Allocate the primary structure
|
||||
PHPacketDataHandle data = pvPortMalloc(sizeof(PHPacketData));
|
||||
if (!data)
|
||||
return 0;
|
||||
data->cfg = *cfg;
|
||||
|
||||
// Allocate the packet windows
|
||||
data->tx_packets = pvPortMalloc(sizeof(PHPacket) * data->cfg.win_size);
|
||||
data->rx_packets = pvPortMalloc(sizeof(PHPacket) * data->cfg.win_size);
|
||||
|
||||
// Initialize the windows
|
||||
data->tx_win_start = data->tx_win_end = 0;
|
||||
data->rx_win_start = data->rx_win_end = 0;
|
||||
for (uint8_t i = 0; i < data->cfg.win_size; ++i)
|
||||
{
|
||||
data->tx_packets[i].header.type = PACKET_TYPE_NONE;
|
||||
data->rx_packets[i].header.type = PACKET_TYPE_NONE;
|
||||
}
|
||||
|
||||
// Create the lock
|
||||
data->lock = xSemaphoreCreateRecursiveMutex();
|
||||
|
||||
// Initialize the ECC library.
|
||||
initialize_ecc();
|
||||
|
||||
// Initialize the handlers
|
||||
data->output_stream = 0;
|
||||
data->data_handler = 0;
|
||||
data->status_handler = 0;
|
||||
data->ppm_handler = 0;
|
||||
|
||||
// Return the structure.
|
||||
return (PHInstHandle)data;
|
||||
}
|
||||
|
||||
/**
|
||||
* Register an output stream handler
|
||||
* \param[in] h The packet handler instance data pointer.
|
||||
* \param[in] f The output stream handler function
|
||||
*/
|
||||
void PHRegisterOutputStream(PHInstHandle h, PHOutputStream f)
|
||||
{
|
||||
PHPacketDataHandle data = (PHPacketDataHandle)h;
|
||||
|
||||
data->output_stream = f;
|
||||
}
|
||||
|
||||
/**
|
||||
* Register a data handler
|
||||
* \param[in] h The packet handler instance data pointer.
|
||||
* \param[in] f The data handler function
|
||||
*/
|
||||
void PHRegisterDataHandler(PHInstHandle h, PHDataHandler f)
|
||||
{
|
||||
PHPacketDataHandle data = (PHPacketDataHandle)h;
|
||||
|
||||
data->data_handler = f;
|
||||
}
|
||||
|
||||
/**
|
||||
* Register a PPM packet handler
|
||||
* \param[in] h The packet handler instance data pointer.
|
||||
* \param[in] f The PPM handler function
|
||||
*/
|
||||
void PHRegisterStatusHandler(PHInstHandle h, PHStatusHandler f)
|
||||
{
|
||||
PHPacketDataHandle data = (PHPacketDataHandle)h;
|
||||
|
||||
data->status_handler = f;
|
||||
}
|
||||
|
||||
/**
|
||||
* Register a PPM packet handler
|
||||
* \param[in] h The packet handler instance data pointer.
|
||||
* \param[in] f The PPM handler function
|
||||
*/
|
||||
void PHRegisterPPMHandler(PHInstHandle h, PHPPMHandler f)
|
||||
{
|
||||
PHPacketDataHandle data = (PHPacketDataHandle)h;
|
||||
|
||||
data->ppm_handler = f;
|
||||
}
|
||||
|
||||
/**
|
||||
* Get a packet out of the transmit buffer.
|
||||
* \param[in] h The packet handler instance data pointer.
|
||||
* \param[in] dest_id The destination ID of this connection
|
||||
* \return PHPacketHandle A pointer to the packet buffer.
|
||||
* \return 0 No packets buffers avaiable in the transmit window.
|
||||
*/
|
||||
uint32_t PHConnect(PHInstHandle h, uint32_t dest_id)
|
||||
{
|
||||
return 1;
|
||||
}
|
||||
|
||||
/**
|
||||
* Get a packet out of the transmit buffer.
|
||||
* \param[in] h The packet handler instance data pointer.
|
||||
* \return PHPacketHandle A pointer to the packet buffer.
|
||||
* \return 0 No packets buffers avaiable in the transmit window.
|
||||
*/
|
||||
PHPacketHandle PHGetTXPacket(PHInstHandle h)
|
||||
{
|
||||
PHPacketDataHandle data = (PHPacketDataHandle)h;
|
||||
|
||||
// Lock
|
||||
xSemaphoreTakeRecursive(data->lock, portMAX_DELAY);
|
||||
|
||||
// Find a free packet.
|
||||
PHPacketHandle p = NULL;
|
||||
for (uint8_t i = 0; i < data->cfg.win_size; ++i)
|
||||
if (data->tx_packets[i].header.type == PACKET_TYPE_NONE)
|
||||
{
|
||||
p = data->tx_packets + i;
|
||||
break;
|
||||
}
|
||||
|
||||
// Release lock
|
||||
xSemaphoreGiveRecursive(data->lock);
|
||||
|
||||
// Return a pointer to the packet at the end of the TX window.
|
||||
return p;
|
||||
}
|
||||
|
||||
/**
|
||||
* Release a packet from the transmit packet buffer window.
|
||||
* \param[in] h The packet handler instance data pointer.
|
||||
* \param[in] p A pointer to the packet buffer.
|
||||
* \return Nothing
|
||||
*/
|
||||
void PHReleaseTXPacket(PHInstHandle h, PHPacketHandle p)
|
||||
{
|
||||
PHPacketDataHandle data = (PHPacketDataHandle)h;
|
||||
|
||||
// Lock
|
||||
xSemaphoreTakeRecursive(data->lock, portMAX_DELAY);
|
||||
|
||||
// Change the packet type so we know this packet is unused.
|
||||
p->header.type = PACKET_TYPE_NONE;
|
||||
|
||||
// If this packet is at the start of the window, increment the start index.
|
||||
while ((data->tx_win_start != data->tx_win_end) &&
|
||||
(data->tx_packets[data->tx_win_start].header.type == PACKET_TYPE_NONE))
|
||||
data->tx_win_start = (data->tx_win_start + 1) % data->cfg.win_size;
|
||||
|
||||
// Release lock
|
||||
xSemaphoreGiveRecursive(data->lock);
|
||||
}
|
||||
|
||||
/**
|
||||
* Get a packet out of the receive buffer.
|
||||
* \param[in] h The packet handler instance data pointer.
|
||||
* \return PHPacketHandle A pointer to the packet buffer.
|
||||
* \return 0 No packets buffers avaiable in the transmit window.
|
||||
*/
|
||||
PHPacketHandle PHGetRXPacket(PHInstHandle h)
|
||||
{
|
||||
PHPacketDataHandle data = (PHPacketDataHandle)h;
|
||||
|
||||
// Lock
|
||||
xSemaphoreTakeRecursive(data->lock, portMAX_DELAY);
|
||||
|
||||
// Find a free packet.
|
||||
PHPacketHandle p = NULL;
|
||||
for (uint8_t i = 0; i < data->cfg.win_size; ++i)
|
||||
if (data->rx_packets[i].header.type == PACKET_TYPE_NONE)
|
||||
{
|
||||
p = data->rx_packets + i;
|
||||
break;
|
||||
}
|
||||
|
||||
// Release lock
|
||||
xSemaphoreGiveRecursive(data->lock);
|
||||
|
||||
// Return a pointer to the packet at the end of the TX window.
|
||||
return p;
|
||||
}
|
||||
|
||||
/**
|
||||
* Release a packet from the receive packet buffer window.
|
||||
* \param[in] h The packet handler instance data pointer.
|
||||
* \param[in] p A pointer to the packet buffer.
|
||||
* \return Nothing
|
||||
*/
|
||||
void PHReleaseRXPacket(PHInstHandle h, PHPacketHandle p)
|
||||
{
|
||||
PHPacketDataHandle data = (PHPacketDataHandle)h;
|
||||
|
||||
// Lock
|
||||
xSemaphoreTakeRecursive(data->lock, portMAX_DELAY);
|
||||
|
||||
// Change the packet type so we know this packet is unused.
|
||||
p->header.type = PACKET_TYPE_NONE;
|
||||
|
||||
// If this packet is at the start of the window, increment the start index.
|
||||
while ((data->rx_win_start != data->rx_win_end) &&
|
||||
(data->rx_packets[data->rx_win_start].header.type == PACKET_TYPE_NONE))
|
||||
data->rx_win_start = (data->rx_win_start + 1) % data->cfg.win_size;
|
||||
|
||||
// Release lock
|
||||
xSemaphoreGiveRecursive(data->lock);
|
||||
}
|
||||
|
||||
/**
|
||||
* Transmit a packet from the transmit packet buffer window.
|
||||
* \param[in] h The packet handler instance data pointer.
|
||||
* \param[in] p A pointer to the packet buffer.
|
||||
* \return 1 Success
|
||||
* \return 0 Failure
|
||||
*/
|
||||
uint8_t PHTransmitPacket(PHInstHandle h, PHPacketHandle p)
|
||||
{
|
||||
PHPacketDataHandle data = (PHPacketDataHandle)h;
|
||||
|
||||
// Try to transmit the packet.
|
||||
if (!PHLTransmitPacket(data, p))
|
||||
return 0;
|
||||
|
||||
return 1;
|
||||
}
|
||||
|
||||
/**
|
||||
* Transmit a packet of data.
|
||||
* \param[in] h The packet handler instance data pointer.
|
||||
* \param[in] p A pointer to the data buffer.
|
||||
* \param[in] len The length of the data buffer.
|
||||
* \return 1 Success
|
||||
* \return 0 Failure
|
||||
*/
|
||||
uint8_t PHTransmitData(PHInstHandle h, uint8_t *buf, uint16_t len)
|
||||
{
|
||||
PHPacketDataHandle data = (PHPacketDataHandle)h;
|
||||
|
||||
// Get a packet from the packet handler.
|
||||
PHPacketHandle p = PHGetTXPacket(pios_packet_handler);
|
||||
if (!p)
|
||||
return 0;
|
||||
|
||||
// Initialize the packet.
|
||||
p->header.destination_id = data->cfg.default_destination_id;
|
||||
p->header.source_id = data->cfg.source_id;
|
||||
p->header.type = PACKET_TYPE_DATA;
|
||||
p->header.data_size = len;
|
||||
|
||||
// Copy the data into the packet.
|
||||
memcpy(p->data, buf, len);
|
||||
|
||||
// Send the packet.
|
||||
return PHLTransmitPacket(data, p);
|
||||
}
|
||||
|
||||
/**
|
||||
* Process a packet that has been received.
|
||||
* \param[in] h The packet handler instance data pointer.
|
||||
* \param[in] p A pointer to the packet buffer.
|
||||
* \param[in] received_len The length of data received.
|
||||
* \return 0 Failure
|
||||
* \return 1 Success
|
||||
*/
|
||||
uint8_t PHReceivePacket(PHInstHandle h, PHPacketHandle p)
|
||||
{
|
||||
PHPacketDataHandle data = (PHPacketDataHandle)h;
|
||||
uint16_t len = PHPacketSizeECC(p);
|
||||
|
||||
// Extract the RSSI and AFC.
|
||||
int8_t rssi = *(((int8_t*)p) + len);
|
||||
int8_t afc = *(((int8_t*)p) + len + 1);
|
||||
|
||||
switch (p->header.type) {
|
||||
|
||||
case PACKET_TYPE_STATUS:
|
||||
|
||||
// Pass on the channels to the status handler.
|
||||
if(data->status_handler)
|
||||
data->status_handler((PHStatusPacketHandle)p, rssi, afc);
|
||||
break;
|
||||
|
||||
case PACKET_TYPE_PPM:
|
||||
|
||||
// Pass on the channels to the PPM handler.
|
||||
if(data->ppm_handler)
|
||||
data->ppm_handler(((PHPpmPacketHandle)p)->channels);
|
||||
break;
|
||||
|
||||
case PACKET_TYPE_DATA:
|
||||
|
||||
// Pass on the data to the data handler.
|
||||
if(data->data_handler)
|
||||
data->data_handler(p->data, p->header.data_size, rssi, afc);
|
||||
break;
|
||||
|
||||
default:
|
||||
break;
|
||||
}
|
||||
|
||||
// Release the packet.
|
||||
PHReleaseRXPacket(h, p);
|
||||
|
||||
return 1;
|
||||
}
|
||||
|
||||
/**
|
||||
* Transmit a packet from the transmit packet buffer window.
|
||||
* \param[in] data The packet handler instance data pointer.
|
||||
* \param[in] p A pointer to the packet buffer.
|
||||
* \return 1 Success
|
||||
* \return 0 Failure
|
||||
*/
|
||||
static uint8_t PHLTransmitPacket(PHPacketDataHandle data, PHPacketHandle p)
|
||||
{
|
||||
|
||||
if(!data->output_stream)
|
||||
return 0;
|
||||
|
||||
// Transmit the packet using the output stream.
|
||||
if(data->output_stream(p) == -1)
|
||||
return 0;
|
||||
|
||||
return 1;
|
||||
}
|
@ -527,6 +527,9 @@ static bool updateRcvrActivityCompare(uint32_t rcvr_id, struct rcvr_activity_fsm
|
||||
case MANUALCONTROLSETTINGS_CHANNELGROUPS_GCS:
|
||||
group = RECEIVERACTIVITY_ACTIVEGROUP_GCS;
|
||||
break;
|
||||
case MANUALCONTROLSETTINGS_CHANNELGROUPS_OPLINK:
|
||||
group = RECEIVERACTIVITY_ACTIVEGROUP_OPLINK;
|
||||
break;
|
||||
default:
|
||||
PIOS_Assert(0);
|
||||
break;
|
||||
|
@ -39,8 +39,10 @@
|
||||
*/
|
||||
|
||||
#include <openpilot.h>
|
||||
#include <pipxstatus.h>
|
||||
#include <oplinkstatus.h>
|
||||
#include <pios_rfm22b.h>
|
||||
#include <pios_board_info.h>
|
||||
#include <oplinksettings.h>
|
||||
#include "systemmod.h"
|
||||
|
||||
// Private constants
|
||||
@ -94,20 +96,20 @@ int32_t PipXtremeModInitialize(void)
|
||||
// Must registers objects here for system thread because ObjectManager started in OpenPilotInit
|
||||
|
||||
// Initialize out status object.
|
||||
PipXStatusInitialize();
|
||||
PipXStatusData pipxStatus;
|
||||
PipXStatusGet(&pipxStatus);
|
||||
OPLinkStatusInitialize();
|
||||
OPLinkStatusData oplinkStatus;
|
||||
OPLinkStatusGet(&oplinkStatus);
|
||||
|
||||
// Get our hardware information.
|
||||
const struct pios_board_info * bdinfo = &pios_board_info_blob;
|
||||
|
||||
pipxStatus.BoardType= bdinfo->board_type;
|
||||
PIOS_BL_HELPER_FLASH_Read_Description(pipxStatus.Description, PIPXSTATUS_DESCRIPTION_NUMELEM);
|
||||
PIOS_SYS_SerialNumberGetBinary(pipxStatus.CPUSerial);
|
||||
pipxStatus.BoardRevision= bdinfo->board_rev;
|
||||
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
|
||||
PipXStatusSet(&pipxStatus);
|
||||
OPLinkStatusSet(&oplinkStatus);
|
||||
|
||||
// Call the module start function.
|
||||
PipXtremeModStart();
|
||||
@ -123,6 +125,9 @@ MODULE_INITCALL(PipXtremeModInitialize, 0)
|
||||
static void systemTask(void *parameters)
|
||||
{
|
||||
portTickType lastSysTime;
|
||||
uint16_t prev_tx_count = 0;
|
||||
uint16_t prev_rx_count = 0;
|
||||
bool first_time = true;
|
||||
|
||||
/* create all modules thread */
|
||||
MODULE_TASKCREATE_ALL;
|
||||
@ -148,6 +153,58 @@ static void systemTask(void *parameters)
|
||||
PIOS_LED_Toggle(PIOS_LED_HEARTBEAT);
|
||||
#endif /* PIOS_LED_HEARTBEAT */
|
||||
|
||||
// Update the PipXstatus UAVO
|
||||
OPLinkStatusData oplinkStatus;
|
||||
uint32_t pairID;
|
||||
OPLinkStatusGet(&oplinkStatus);
|
||||
OPLinkSettingsPairIDGet(&pairID);
|
||||
|
||||
// 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 status
|
||||
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.AFCCorrection = radio_stats.afc_correction;
|
||||
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;
|
||||
if (radio_stats.link_state == OPLINKSTATUS_LINKSTATE_CONNECTED)
|
||||
LINK_LED_ON;
|
||||
else
|
||||
LINK_LED_OFF;
|
||||
|
||||
// Update the object
|
||||
OPLinkStatusSet(&oplinkStatus);
|
||||
|
||||
// Wait until next period
|
||||
vTaskDelayUntil(&lastSysTime, SYSTEM_UPDATE_PERIOD_MS / portTICK_RATE_MS);
|
||||
}
|
||||
|
@ -1,476 +0,0 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup OpenPilotModules OpenPilot Modules
|
||||
* @{
|
||||
* @addtogroup Radio Input / Output Module
|
||||
* @brief Read and Write packets from/to a radio device.
|
||||
* @{
|
||||
*
|
||||
* @file radio.c
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @brief Bridges selected Com Port to the COM VCP emulated serial port
|
||||
* @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>
|
||||
#include <pios_board_info.h>
|
||||
#include <openpilot.h>
|
||||
#include <gcsreceiver.h>
|
||||
#include <hwsettings.h>
|
||||
#include <pipxsettings.h>
|
||||
#include <pipxstatus.h>
|
||||
#include <packet_handler.h>
|
||||
#include <pios_com_priv.h>
|
||||
#include <pios_rfm22b_priv.h>
|
||||
#include <radio.h>
|
||||
|
||||
// ****************
|
||||
// Private constants
|
||||
|
||||
#define STACK_SIZE_BYTES 200
|
||||
#define TASK_PRIORITY (tskIDLE_PRIORITY + 2)
|
||||
#define PACKET_QUEUE_SIZE PIOS_PH_WIN_SIZE
|
||||
#define MAX_PORT_DELAY 200
|
||||
#define STATS_UPDATE_PERIOD_MS 500
|
||||
#define RADIOSTATS_UPDATE_PERIOD_MS 250
|
||||
#define MAX_LOST_CONTACT_TIME 4
|
||||
#define PACKET_MAX_DELAY 50
|
||||
|
||||
#ifndef LINK_LED_ON
|
||||
#define LINK_LED_ON
|
||||
#define LINK_LED_OFF
|
||||
#endif
|
||||
|
||||
// ****************
|
||||
// Private types
|
||||
|
||||
typedef struct {
|
||||
uint32_t pairID;
|
||||
uint16_t retries;
|
||||
uint16_t errors;
|
||||
uint16_t uavtalk_errors;
|
||||
uint16_t resets;
|
||||
uint16_t dropped;
|
||||
int8_t rssi;
|
||||
uint8_t lastContact;
|
||||
} PairStats;
|
||||
|
||||
typedef struct {
|
||||
|
||||
// The task handles.
|
||||
xTaskHandle radioReceiveTaskHandle;
|
||||
xTaskHandle radioStatusTaskHandle;
|
||||
|
||||
// Queue handles.
|
||||
xQueueHandle radioPacketQueue;
|
||||
|
||||
// Error statistics.
|
||||
uint32_t radioTxErrors;
|
||||
uint32_t radioRxErrors;
|
||||
uint16_t txBytes;
|
||||
uint16_t rxBytes;
|
||||
|
||||
// External error statistics
|
||||
uint32_t droppedPackets;
|
||||
uint32_t comTxRetries;
|
||||
uint32_t UAVTalkErrors;
|
||||
|
||||
// The destination ID
|
||||
uint32_t destination_id;
|
||||
|
||||
// Track other radios that are in range.
|
||||
PairStats pairStats[PIPXSTATUS_PAIRIDS_NUMELEM];
|
||||
|
||||
// The RSSI of the last packet received.
|
||||
int8_t RSSI;
|
||||
|
||||
} RadioData;
|
||||
|
||||
// ****************
|
||||
// Private functions
|
||||
|
||||
static void radioReceiveTask(void *parameters);
|
||||
static void radioStatusTask(void *parameters);
|
||||
static void StatusHandler(PHStatusPacketHandle p, int8_t rssi, int8_t afc);
|
||||
static int32_t transmitPacket(PHPacketHandle packet);
|
||||
static void PPMHandler(uint16_t *channels);
|
||||
|
||||
// ****************
|
||||
// Private variables
|
||||
|
||||
static RadioData *data = 0;
|
||||
|
||||
// ****************
|
||||
// Global variables
|
||||
uint32_t pios_rfm22b_id = 0;
|
||||
uint32_t pios_com_rfm22b_id = 0;
|
||||
uint32_t pios_packet_handler = 0;
|
||||
const struct pios_rfm22b_cfg *pios_rfm22b_cfg;
|
||||
|
||||
// ***************
|
||||
// External functions
|
||||
extern const struct pios_rfm22b_cfg * PIOS_BOARD_HW_DEFS_GetRfm22Cfg (uint32_t board_revision);
|
||||
|
||||
/**
|
||||
* Start the module
|
||||
* \return -1 if initialisation failed
|
||||
* \return 0 on success
|
||||
*/
|
||||
static int32_t RadioStart(void)
|
||||
{
|
||||
if (!data)
|
||||
return -1;
|
||||
|
||||
// Start the tasks.
|
||||
xTaskCreate(radioReceiveTask, (signed char *)"RadioReceive", STACK_SIZE_BYTES, NULL, TASK_PRIORITY, &(data->radioReceiveTaskHandle));
|
||||
xTaskCreate(radioStatusTask, (signed char *)"RadioStatus", STACK_SIZE_BYTES * 2, NULL, TASK_PRIORITY, &(data->radioStatusTaskHandle));
|
||||
|
||||
// Install the monitors
|
||||
TaskMonitorAdd(TASKINFO_RUNNING_MODEMRX, data->radioReceiveTaskHandle);
|
||||
TaskMonitorAdd(TASKINFO_RUNNING_MODEMSTAT, data->radioStatusTaskHandle);
|
||||
|
||||
// Register the watchdog timers.
|
||||
#ifdef PIOS_WDG_RADIORECEIVE
|
||||
PIOS_WDG_RegisterFlag(PIOS_WDG_RADIORECEIVE);
|
||||
#endif /* PIOS_WDG_RADIORECEIVE */
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* Initialise the module
|
||||
* \return -1 if initialisation failed
|
||||
* \return 0 on success
|
||||
*/
|
||||
static int32_t RadioInitialize(void)
|
||||
{
|
||||
|
||||
// See if this module is enabled.
|
||||
#ifndef RADIO_BUILTIN
|
||||
HwSettingsInitialize();
|
||||
uint8_t optionalModules[HWSETTINGS_OPTIONALMODULES_NUMELEM];
|
||||
HwSettingsOptionalModulesGet(optionalModules);
|
||||
if (optionalModules[HWSETTINGS_OPTIONALMODULES_RADIO] != HWSETTINGS_OPTIONALMODULES_ENABLED) {
|
||||
pios_packet_handler = 0;
|
||||
return -1;
|
||||
}
|
||||
#endif
|
||||
|
||||
// Initalize out UAVOs
|
||||
PipXSettingsInitialize();
|
||||
PipXStatusInitialize();
|
||||
|
||||
PipXSettingsData pipxSettings;
|
||||
PipXSettingsGet(&pipxSettings);
|
||||
|
||||
/* Retrieve hardware settings. */
|
||||
const struct pios_board_info * bdinfo = &pios_board_info_blob;
|
||||
pios_rfm22b_cfg = PIOS_BOARD_HW_DEFS_GetRfm22Cfg(bdinfo->board_rev);
|
||||
|
||||
/* Initalize the RFM22B radio COM device. */
|
||||
if (PIOS_RFM22B_Init(&pios_rfm22b_id, PIOS_RFM22_SPI_PORT, pios_rfm22b_cfg->slave_num, pios_rfm22b_cfg))
|
||||
return -1;
|
||||
|
||||
// Set the maximum radio RF power.
|
||||
switch (pipxSettings.MaxRFPower)
|
||||
{
|
||||
case PIPXSETTINGS_MAXRFPOWER_125:
|
||||
PIOS_RFM22B_SetTxPower(pios_rfm22b_id, RFM22_tx_pwr_txpow_0);
|
||||
break;
|
||||
case PIPXSETTINGS_MAXRFPOWER_16:
|
||||
PIOS_RFM22B_SetTxPower(pios_rfm22b_id, RFM22_tx_pwr_txpow_1);
|
||||
break;
|
||||
case PIPXSETTINGS_MAXRFPOWER_316:
|
||||
PIOS_RFM22B_SetTxPower(pios_rfm22b_id, RFM22_tx_pwr_txpow_2);
|
||||
break;
|
||||
case PIPXSETTINGS_MAXRFPOWER_63:
|
||||
PIOS_RFM22B_SetTxPower(pios_rfm22b_id, RFM22_tx_pwr_txpow_3);
|
||||
break;
|
||||
case PIPXSETTINGS_MAXRFPOWER_126:
|
||||
PIOS_RFM22B_SetTxPower(pios_rfm22b_id, RFM22_tx_pwr_txpow_4);
|
||||
break;
|
||||
case PIPXSETTINGS_MAXRFPOWER_25:
|
||||
PIOS_RFM22B_SetTxPower(pios_rfm22b_id, RFM22_tx_pwr_txpow_5);
|
||||
break;
|
||||
case PIPXSETTINGS_MAXRFPOWER_50:
|
||||
PIOS_RFM22B_SetTxPower(pios_rfm22b_id, RFM22_tx_pwr_txpow_6);
|
||||
break;
|
||||
case PIPXSETTINGS_MAXRFPOWER_100:
|
||||
PIOS_RFM22B_SetTxPower(pios_rfm22b_id, RFM22_tx_pwr_txpow_7);
|
||||
break;
|
||||
}
|
||||
|
||||
switch (pipxSettings.RFSpeed) {
|
||||
case PIPXSETTINGS_RFSPEED_2400:
|
||||
RFM22_SetDatarate(pios_rfm22b_id, RFM22_datarate_2000, true);
|
||||
break;
|
||||
case PIPXSETTINGS_RFSPEED_4800:
|
||||
RFM22_SetDatarate(pios_rfm22b_id, RFM22_datarate_4000, true);
|
||||
break;
|
||||
case PIPXSETTINGS_RFSPEED_9600:
|
||||
RFM22_SetDatarate(pios_rfm22b_id, RFM22_datarate_9600, true);
|
||||
break;
|
||||
case PIPXSETTINGS_RFSPEED_19200:
|
||||
RFM22_SetDatarate(pios_rfm22b_id, RFM22_datarate_19200, true);
|
||||
break;
|
||||
case PIPXSETTINGS_RFSPEED_38400:
|
||||
RFM22_SetDatarate(pios_rfm22b_id, RFM22_datarate_32000, true);
|
||||
break;
|
||||
case PIPXSETTINGS_RFSPEED_57600:
|
||||
RFM22_SetDatarate(pios_rfm22b_id, RFM22_datarate_64000, true);
|
||||
break;
|
||||
case PIPXSETTINGS_RFSPEED_115200:
|
||||
RFM22_SetDatarate(pios_rfm22b_id, RFM22_datarate_128000, true);
|
||||
break;
|
||||
}
|
||||
|
||||
// Set the radio destination ID.
|
||||
PIOS_RFM22B_SetDestinationId(pios_rfm22b_id, pipxSettings.PairID);
|
||||
|
||||
// Initialize the packet handler
|
||||
PacketHandlerConfig pios_ph_cfg = {
|
||||
.default_destination_id = 0xffffffff, // Broadcast
|
||||
.source_id = PIOS_RFM22B_DeviceID(pios_rfm22b_id),
|
||||
.win_size = PIOS_PH_WIN_SIZE,
|
||||
.max_connections = PIOS_PH_MAX_CONNECTIONS,
|
||||
};
|
||||
pios_packet_handler = PHInitialize(&pios_ph_cfg);
|
||||
|
||||
// allocate and initialize the static data storage only if module is enabled
|
||||
data = (RadioData *)pvPortMalloc(sizeof(RadioData));
|
||||
if (!data)
|
||||
return -1;
|
||||
|
||||
// Initialize the statistics.
|
||||
data->radioTxErrors = 0;
|
||||
data->radioRxErrors = 0;
|
||||
data->droppedPackets = 0;
|
||||
data->comTxRetries = 0;
|
||||
data->UAVTalkErrors = 0;
|
||||
data->RSSI = -127;
|
||||
|
||||
// Initialize the detected device statistics.
|
||||
for (uint8_t i = 0; i < PIPXSTATUS_PAIRIDS_NUMELEM; ++i)
|
||||
{
|
||||
data->pairStats[i].pairID = 0;
|
||||
data->pairStats[i].rssi = -127;
|
||||
data->pairStats[i].retries = 0;
|
||||
data->pairStats[i].errors = 0;
|
||||
data->pairStats[i].uavtalk_errors = 0;
|
||||
data->pairStats[i].resets = 0;
|
||||
data->pairStats[i].dropped = 0;
|
||||
data->pairStats[i].lastContact = 0;
|
||||
}
|
||||
// The first slot is reserved for our current pairID
|
||||
PipXSettingsPairIDGet(&(data->pairStats[0].pairID));
|
||||
data->destination_id = data->pairStats[0].pairID ? data->pairStats[0].pairID : 0xffffffff;
|
||||
|
||||
// Register the callbacks with the packet handler
|
||||
PHRegisterStatusHandler(pios_packet_handler, StatusHandler);
|
||||
PHRegisterOutputStream(pios_packet_handler, transmitPacket);
|
||||
PHRegisterPPMHandler(pios_packet_handler, PPMHandler);
|
||||
|
||||
return 0;
|
||||
}
|
||||
MODULE_INITCALL(RadioInitialize, RadioStart)
|
||||
|
||||
/**
|
||||
* The task that receives packets from the radio.
|
||||
*/
|
||||
static void radioReceiveTask(void *parameters)
|
||||
{
|
||||
PHPacketHandle p = NULL;
|
||||
|
||||
/* Handle radio -> usart/usb direction */
|
||||
while (1) {
|
||||
uint32_t rx_bytes;
|
||||
|
||||
#ifdef PIOS_WDG_RADIORECEIVE
|
||||
// Update the watchdog timer.
|
||||
PIOS_WDG_UpdateFlag(PIOS_WDG_RADIORECEIVE);
|
||||
#endif /* PIOS_INCLUDE_WDG */
|
||||
|
||||
// Receive data from the radio port
|
||||
p = NULL;
|
||||
rx_bytes = PIOS_RFM22B_Receive_Packet(pios_rfm22b_id, &p, MAX_PORT_DELAY);
|
||||
if(rx_bytes == 0)
|
||||
continue;
|
||||
data->rxBytes += rx_bytes;
|
||||
PHReceivePacket(pios_packet_handler, p);
|
||||
p = NULL;
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Transmit a packet to the radio port.
|
||||
* \param[in] buf Data buffer to send
|
||||
* \param[in] length Length of buffer
|
||||
* \return -1 on failure
|
||||
* \return number of bytes transmitted on success
|
||||
*/
|
||||
static int32_t transmitPacket(PHPacketHandle p)
|
||||
{
|
||||
uint16_t len = PH_PACKET_SIZE(p);
|
||||
data->txBytes += len;
|
||||
if (!PIOS_RFM22B_Send_Packet(pios_rfm22b_id, p, PACKET_MAX_DELAY))
|
||||
return -1;
|
||||
return len;
|
||||
}
|
||||
|
||||
/**
|
||||
* Receive a status packet
|
||||
* \param[in] status The status structure
|
||||
*/
|
||||
static void StatusHandler(PHStatusPacketHandle status, int8_t rssi, int8_t afc)
|
||||
{
|
||||
uint32_t id = status->header.source_id;
|
||||
bool found = false;
|
||||
// Have we seen this device recently?
|
||||
uint8_t id_idx = 0;
|
||||
for ( ; id_idx < PIPXSTATUS_PAIRIDS_NUMELEM; ++id_idx)
|
||||
if(data->pairStats[id_idx].pairID == id)
|
||||
{
|
||||
found = true;
|
||||
break;
|
||||
}
|
||||
|
||||
// If we have seen it, update the RSSI and reset the last contact couter
|
||||
if(found)
|
||||
{
|
||||
data->pairStats[id_idx].rssi = rssi;
|
||||
data->pairStats[id_idx].retries = status->retries;
|
||||
data->pairStats[id_idx].errors = status->errors;
|
||||
data->pairStats[id_idx].uavtalk_errors = status->uavtalk_errors;
|
||||
data->pairStats[id_idx].resets = status->resets;
|
||||
data->pairStats[id_idx].dropped = status->dropped;
|
||||
data->pairStats[id_idx].lastContact = 0;
|
||||
}
|
||||
|
||||
// If we haven't seen it, find a slot to put it in.
|
||||
if (!found)
|
||||
{
|
||||
uint32_t pairID;
|
||||
PipXSettingsPairIDGet(&pairID);
|
||||
|
||||
uint8_t min_idx = 0;
|
||||
if(id != pairID)
|
||||
{
|
||||
int8_t min_rssi = data->pairStats[0].rssi;
|
||||
for (id_idx = 1; id_idx < PIPXSTATUS_PAIRIDS_NUMELEM; ++id_idx)
|
||||
{
|
||||
if(data->pairStats[id_idx].rssi < min_rssi)
|
||||
{
|
||||
min_rssi = data->pairStats[id_idx].rssi;
|
||||
min_idx = id_idx;
|
||||
}
|
||||
}
|
||||
}
|
||||
data->pairStats[min_idx].pairID = id;
|
||||
data->pairStats[min_idx].rssi = rssi;
|
||||
data->pairStats[min_idx].retries = status->retries;
|
||||
data->pairStats[min_idx].errors = status->errors;
|
||||
data->pairStats[min_idx].uavtalk_errors = status->uavtalk_errors;
|
||||
data->pairStats[min_idx].resets = status->resets;
|
||||
data->pairStats[min_idx].dropped = status->dropped;
|
||||
data->pairStats[min_idx].lastContact = 0;
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* The stats update task.
|
||||
*/
|
||||
static void radioStatusTask(void *parameters)
|
||||
{
|
||||
while (1) {
|
||||
PipXStatusData pipxStatus;
|
||||
uint32_t pairID;
|
||||
|
||||
// Get object data
|
||||
PipXStatusGet(&pipxStatus);
|
||||
PipXSettingsPairIDGet(&pairID);
|
||||
|
||||
// Update the status
|
||||
pipxStatus.DeviceID = PIOS_RFM22B_DeviceID(pios_rfm22b_id);
|
||||
pipxStatus.Retries = data->comTxRetries;
|
||||
pipxStatus.LinkQuality = PIOS_RFM22B_LinkQuality(pios_rfm22b_id);
|
||||
pipxStatus.UAVTalkErrors = data->UAVTalkErrors;
|
||||
pipxStatus.Dropped = data->droppedPackets;
|
||||
pipxStatus.Resets = PIOS_RFM22B_Resets(pios_rfm22b_id);
|
||||
pipxStatus.TXRate = (uint16_t)((float)(data->txBytes * 1000) / STATS_UPDATE_PERIOD_MS);
|
||||
data->txBytes = 0;
|
||||
pipxStatus.RXRate = (uint16_t)((float)(data->rxBytes * 1000) / STATS_UPDATE_PERIOD_MS);
|
||||
data->rxBytes = 0;
|
||||
pipxStatus.LinkState = PIPXSTATUS_LINKSTATE_DISCONNECTED;
|
||||
pipxStatus.RSSI = PIOS_RFM22B_LinkQuality(pios_rfm22b_id);
|
||||
LINK_LED_OFF;
|
||||
|
||||
// Update the potential pairing contacts
|
||||
for (uint8_t i = 0; i < PIPXSTATUS_PAIRIDS_NUMELEM; ++i)
|
||||
{
|
||||
pipxStatus.PairIDs[i] = data->pairStats[i].pairID;
|
||||
pipxStatus.PairSignalStrengths[i] = data->pairStats[i].rssi;
|
||||
data->pairStats[i].lastContact++;
|
||||
// Remove this device if it's stale.
|
||||
if(data->pairStats[i].lastContact > MAX_LOST_CONTACT_TIME)
|
||||
{
|
||||
data->pairStats[i].pairID = 0;
|
||||
data->pairStats[i].rssi = -127;
|
||||
data->pairStats[i].retries = 0;
|
||||
data->pairStats[i].errors = 0;
|
||||
data->pairStats[i].uavtalk_errors = 0;
|
||||
data->pairStats[i].resets = 0;
|
||||
data->pairStats[i].dropped = 0;
|
||||
data->pairStats[i].lastContact = 0;
|
||||
}
|
||||
// Add the paired devices statistics to ours.
|
||||
if(pairID && (data->pairStats[i].pairID == pairID) && (data->pairStats[i].rssi > -127))
|
||||
{
|
||||
pipxStatus.Retries += data->pairStats[i].retries;
|
||||
pipxStatus.UAVTalkErrors += data->pairStats[i].uavtalk_errors;
|
||||
pipxStatus.Dropped += data->pairStats[i].dropped;
|
||||
pipxStatus.Resets += data->pairStats[i].resets;
|
||||
pipxStatus.Dropped += data->pairStats[i].dropped;
|
||||
pipxStatus.LinkState = PIPXSTATUS_LINKSTATE_CONNECTED;
|
||||
LINK_LED_ON;
|
||||
}
|
||||
}
|
||||
|
||||
// Update the object
|
||||
PipXStatusSet(&pipxStatus);
|
||||
|
||||
vTaskDelay(STATS_UPDATE_PERIOD_MS / portTICK_RATE_MS);
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Receive a ppm packet
|
||||
* \param[in] channels The ppm channels
|
||||
*/
|
||||
static void PPMHandler(uint16_t *channels)
|
||||
{
|
||||
GCSReceiverData rcvr;
|
||||
|
||||
// Copy the receiver channels into the GCSReceiver object.
|
||||
for (uint8_t i = 0; i < GCSRECEIVER_CHANNEL_NUMELEM; ++i)
|
||||
rcvr.Channel[i] = channels[i];
|
||||
|
||||
// Set the GCSReceiverData object.
|
||||
GCSReceiverSet(&rcvr);
|
||||
}
|
@ -34,9 +34,9 @@
|
||||
#include <radiocombridge.h>
|
||||
#include <packet_handler.h>
|
||||
#include <gcsreceiver.h>
|
||||
#include <pipxstatus.h>
|
||||
#include <oplinkstatus.h>
|
||||
#include <objectpersistence.h>
|
||||
#include <pipxsettings.h>
|
||||
#include <oplinksettings.h>
|
||||
#include <uavtalk_priv.h>
|
||||
#include <pios_rfm22b.h>
|
||||
#include <ecc.h>
|
||||
@ -49,46 +49,28 @@
|
||||
// ****************
|
||||
// Private constants
|
||||
|
||||
#define TEMP_BUFFER_SIZE 25
|
||||
#define STACK_SIZE_BYTES 150
|
||||
#define TASK_PRIORITY (tskIDLE_PRIORITY + 1)
|
||||
#define BRIDGE_BUF_LEN 512
|
||||
#define MAX_RETRIES 2
|
||||
#define RETRY_TIMEOUT_MS 20
|
||||
#define STATS_UPDATE_PERIOD_MS 1000
|
||||
#define RADIOSTATS_UPDATE_PERIOD_MS 500
|
||||
#define MAX_LOST_CONTACT_TIME 4
|
||||
#define PACKET_QUEUE_SIZE 10
|
||||
#define EVENT_QUEUE_SIZE 10
|
||||
#define MAX_PORT_DELAY 200
|
||||
#define EV_PACKET_RECEIVED 0x20
|
||||
#define EV_TRANSMIT_PACKET 0x30
|
||||
#define EV_SEND_ACK 0x40
|
||||
#define EV_SEND_NACK 0x50
|
||||
#define EV_SEND_ACK 0x20
|
||||
#define EV_SEND_NACK 0x30
|
||||
|
||||
// ****************
|
||||
// Private types
|
||||
|
||||
typedef struct {
|
||||
uint32_t comPort;
|
||||
UAVTalkConnection UAVTalkCon;
|
||||
xQueueHandle sendQueue;
|
||||
xQueueHandle recvQueue;
|
||||
uint16_t wdg;
|
||||
bool isGCS;
|
||||
} UAVTalkComTaskParams;
|
||||
|
||||
typedef struct {
|
||||
|
||||
// The task handles.
|
||||
xTaskHandle GCSUAVTalkRecvTaskHandle;
|
||||
xTaskHandle UAVTalkRecvTaskHandle;
|
||||
xTaskHandle UAVTalkSendTaskHandle;
|
||||
xTaskHandle transparentCommTaskHandle;
|
||||
xTaskHandle ppmInputTaskHandle;
|
||||
xTaskHandle telemetryTxTaskHandle;
|
||||
xTaskHandle radioRxTaskHandle;
|
||||
xTaskHandle radioTxTaskHandle;
|
||||
|
||||
// The UAVTalk connection on the com side.
|
||||
UAVTalkConnection UAVTalkCon;
|
||||
UAVTalkConnection GCSUAVTalkCon;
|
||||
UAVTalkConnection outUAVTalkCon;
|
||||
UAVTalkConnection inUAVTalkCon;
|
||||
|
||||
// Queue handles.
|
||||
xQueueHandle gcsEventQueue;
|
||||
@ -100,45 +82,19 @@ typedef struct {
|
||||
uint32_t UAVTalkErrors;
|
||||
uint32_t droppedPackets;
|
||||
|
||||
// The destination ID
|
||||
uint32_t destination_id;
|
||||
|
||||
// The packet timeout.
|
||||
portTickType send_timeout;
|
||||
uint16_t min_packet_size;
|
||||
|
||||
// The RSSI of the last packet received.
|
||||
int8_t RSSI;
|
||||
|
||||
// Thread parameters.
|
||||
UAVTalkComTaskParams uavtalk_params;
|
||||
UAVTalkComTaskParams gcs_uavtalk_params;
|
||||
|
||||
} RadioComBridgeData;
|
||||
|
||||
typedef struct {
|
||||
uint32_t com_port;
|
||||
uint8_t *buffer;
|
||||
uint16_t length;
|
||||
uint16_t index;
|
||||
uint16_t data_length;
|
||||
} ReadBuffer, *BufferedReadHandle;
|
||||
|
||||
// ****************
|
||||
// Private functions
|
||||
|
||||
static void UAVTalkRecvTask(void *parameters);
|
||||
static void UAVTalkSendTask(void *parameters);
|
||||
static void transparentCommTask(void * parameters);
|
||||
static void ppmInputTask(void *parameters);
|
||||
static int32_t UAVTalkSendHandler(uint8_t * data, int32_t length);
|
||||
static int32_t GCSUAVTalkSendHandler(uint8_t * data, int32_t length);
|
||||
static void receiveData(uint8_t *buf, uint8_t len, int8_t rssi, int8_t afc);
|
||||
static void transmitData(uint32_t outputPort, uint8_t *buf, uint8_t len, bool checkHid);
|
||||
static BufferedReadHandle BufferedReadInit(uint32_t com_port, uint16_t buffer_length);
|
||||
static bool BufferedRead(BufferedReadHandle h, uint8_t *value, uint32_t timeout_ms);
|
||||
static void BufferedReadSetCom(BufferedReadHandle h, uint32_t com_port);
|
||||
static void telemetryTxTask(void *parameters);
|
||||
static void radioRxTask(void *parameters);
|
||||
static void radioTxTask(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(OPLinkSettingsOutputConnectionOptions com_port, OPLinkSettingsComSpeedOptions com_speed);
|
||||
static void updateSettings();
|
||||
|
||||
// ****************
|
||||
@ -155,37 +111,24 @@ static int32_t RadioComBridgeStart(void)
|
||||
{
|
||||
if(data) {
|
||||
|
||||
// Register the callbacks with the packet handler
|
||||
// This has to happen after the Radio module is initialized.
|
||||
PHRegisterDataHandler(pios_packet_handler, receiveData);
|
||||
// Configure the com port configuration callback
|
||||
PIOS_RFM22B_SetComConfigCallback(pios_rfm22b_id, &configureComCallback);
|
||||
|
||||
// Set the baudrates, etc.
|
||||
updateSettings();
|
||||
|
||||
// Start the primary tasks for receiving/sending UAVTalk packets from the GCS.
|
||||
xTaskCreate(UAVTalkRecvTask, (signed char *)"GCSUAVTalkRecvTask", STACK_SIZE_BYTES, (void*)&(data->gcs_uavtalk_params), TASK_PRIORITY + 2, &(data->GCSUAVTalkRecvTaskHandle));
|
||||
xTaskCreate(UAVTalkSendTask, (signed char *)"GCSUAVTalkSendTask", STACK_SIZE_BYTES, (void*)&(data->gcs_uavtalk_params), TASK_PRIORITY+ 2, &(data->UAVTalkSendTaskHandle));
|
||||
|
||||
// If a UAVTalk (non-GCS) com port is set it implies that the com port is connected on the flight side.
|
||||
// In this case we want to start another com thread on the HID port to talk to the GCS when connected.
|
||||
if (PIOS_COM_UAVTALK)
|
||||
{
|
||||
xTaskCreate(UAVTalkRecvTask, (signed char *)"UAVTalkRecvTask", STACK_SIZE_BYTES, (void*)&(data->uavtalk_params), TASK_PRIORITY + 2, &(data->UAVTalkRecvTaskHandle));
|
||||
xTaskCreate(UAVTalkSendTask, (signed char *)"UAVTalkSendTask", STACK_SIZE_BYTES, (void*)&(data->uavtalk_params), TASK_PRIORITY+ 2, &(data->UAVTalkSendTaskHandle));
|
||||
}
|
||||
|
||||
// Start the tasks
|
||||
if(PIOS_COM_TRANS_COM)
|
||||
xTaskCreate(transparentCommTask, (signed char *)"transparentComm", STACK_SIZE_BYTES, NULL, TASK_PRIORITY + 2, &(data->transparentCommTaskHandle));
|
||||
if(PIOS_PPM_RECEIVER)
|
||||
xTaskCreate(ppmInputTask, (signed char *)"PPMInputTask", STACK_SIZE_BYTES, NULL, TASK_PRIORITY + 2, &(data->ppmInputTaskHandle));
|
||||
xTaskCreate(telemetryTxTask, (signed char *)"telemTxTask", STACK_SIZE_BYTES, NULL, TASK_PRIORITY, &(data->telemetryTxTaskHandle));
|
||||
xTaskCreate(radioRxTask, (signed char *)"radioRxTask", STACK_SIZE_BYTES, NULL, TASK_PRIORITY, &(data->radioRxTaskHandle));
|
||||
xTaskCreate(radioTxTask, (signed char *)"radioTxTask", STACK_SIZE_BYTES, NULL, TASK_PRIORITY, &(data->radioTxTaskHandle));
|
||||
|
||||
// Register the watchdog timers.
|
||||
#ifdef PIOS_INCLUDE_WDG
|
||||
PIOS_WDG_RegisterFlag(PIOS_WDG_COMGCS);
|
||||
if(PIOS_COM_UAVTALK)
|
||||
PIOS_WDG_RegisterFlag(PIOS_WDG_COMUAVTALK);
|
||||
if(PIOS_COM_TRANS_COM)
|
||||
PIOS_WDG_RegisterFlag(PIOS_WDG_TRANSCOMM);
|
||||
if(PIOS_PPM_RECEIVER)
|
||||
PIOS_WDG_RegisterFlag(PIOS_WDG_PPMINPUT);
|
||||
PIOS_WDG_RegisterFlag(PIOS_WDG_TELEMETRY);
|
||||
PIOS_WDG_RegisterFlag(PIOS_WDG_RADIORX);
|
||||
PIOS_WDG_RegisterFlag(PIOS_WDG_RADIOTX);
|
||||
#endif
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
@ -207,315 +150,50 @@ static int32_t RadioComBridgeInitialize(void)
|
||||
|
||||
// Initialize the UAVObjects that we use
|
||||
GCSReceiverInitialize();
|
||||
PipXStatusInitialize();
|
||||
OPLinkStatusInitialize();
|
||||
ObjectPersistenceInitialize();
|
||||
updateSettings();
|
||||
|
||||
// Initialise UAVTalk
|
||||
data->GCSUAVTalkCon = UAVTalkInitialize(&GCSUAVTalkSendHandler);
|
||||
if (PIOS_COM_UAVTALK)
|
||||
data->UAVTalkCon = UAVTalkInitialize(&UAVTalkSendHandler);
|
||||
else
|
||||
data->UAVTalkCon = 0;
|
||||
data->outUAVTalkCon = UAVTalkInitialize(&UAVTalkSendHandler);
|
||||
data->inUAVTalkCon = UAVTalkInitialize(&RadioSendHandler);
|
||||
|
||||
// Initialize the queues.
|
||||
data->gcsEventQueue = xQueueCreate(PACKET_QUEUE_SIZE, sizeof(UAVObjEvent));
|
||||
if (PIOS_COM_UAVTALK)
|
||||
data->uavtalkEventQueue = xQueueCreate(PACKET_QUEUE_SIZE, sizeof(UAVObjEvent));
|
||||
else
|
||||
{
|
||||
data->uavtalkEventQueue = 0;
|
||||
}
|
||||
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);
|
||||
|
||||
// Initialize the statistics.
|
||||
data->comTxErrors = 0;
|
||||
data->comTxRetries = 0;
|
||||
data->UAVTalkErrors = 0;
|
||||
data->RSSI = -127;
|
||||
|
||||
// Initialize the packet send timeout
|
||||
data->send_timeout = 25; // ms
|
||||
data->min_packet_size = 50;
|
||||
|
||||
// Configure our UAVObjects for updates.
|
||||
UAVObjConnectQueue(UAVObjGetByID(PIPXSTATUS_OBJID), data->gcsEventQueue, EV_UPDATED | EV_UPDATED_MANUAL | EV_UPDATE_REQ);
|
||||
UAVObjConnectQueue(UAVObjGetByID(GCSRECEIVER_OBJID), data->uavtalkEventQueue ? data->uavtalkEventQueue : data->gcsEventQueue, EV_UPDATED | EV_UPDATED_MANUAL | EV_UPDATE_REQ);
|
||||
UAVObjConnectQueue(UAVObjGetByID(OBJECTPERSISTENCE_OBJID), data->gcsEventQueue, EV_UPDATED | EV_UPDATED_MANUAL);
|
||||
|
||||
// Initialize the UAVTalk comm parameters.
|
||||
data->gcs_uavtalk_params.isGCS = true;
|
||||
data->gcs_uavtalk_params.UAVTalkCon = data->GCSUAVTalkCon;
|
||||
data->gcs_uavtalk_params.sendQueue = data->uavtalkEventQueue;
|
||||
data->gcs_uavtalk_params.recvQueue = data->gcsEventQueue;
|
||||
data->gcs_uavtalk_params.wdg = PIOS_WDG_COMGCS;
|
||||
data->gcs_uavtalk_params.comPort = PIOS_COM_GCS;
|
||||
if (PIOS_COM_UAVTALK)
|
||||
{
|
||||
data->uavtalk_params.isGCS = false;
|
||||
data->uavtalk_params.UAVTalkCon = data->UAVTalkCon;
|
||||
data->uavtalk_params.sendQueue = data->gcsEventQueue;
|
||||
data->uavtalk_params.recvQueue = data->uavtalkEventQueue;
|
||||
data->uavtalk_params.wdg = PIOS_WDG_COMUAVTALK;
|
||||
data->uavtalk_params.comPort = PIOS_COM_UAVTALK;
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
MODULE_INITCALL(RadioComBridgeInitialize, RadioComBridgeStart)
|
||||
|
||||
/**
|
||||
* Reads UAVTalk messages froma com port and creates packets out of them.
|
||||
* Telemetry transmit task, regular priority
|
||||
*/
|
||||
static void UAVTalkRecvTask(void *parameters)
|
||||
static void telemetryTxTask(void *parameters)
|
||||
{
|
||||
UAVTalkComTaskParams *params = (UAVTalkComTaskParams *)parameters;
|
||||
PHPacketHandle p = NULL;
|
||||
|
||||
// Create the buffered reader.
|
||||
BufferedReadHandle f = BufferedReadInit(params->comPort, TEMP_BUFFER_SIZE);
|
||||
|
||||
while (1) {
|
||||
bool HID_available = false;
|
||||
xQueueHandle sendQueue = 0;
|
||||
|
||||
#ifdef PIOS_INCLUDE_WDG
|
||||
// Update the watchdog timer.
|
||||
if (params->wdg)
|
||||
PIOS_WDG_UpdateFlag(params->wdg);
|
||||
#endif /* PIOS_INCLUDE_WDG */
|
||||
|
||||
#if defined(PIOS_INCLUDE_USB)
|
||||
// Is USB plugged in?
|
||||
if (PIOS_USB_CheckAvailable(0))
|
||||
HID_available = true;
|
||||
#endif /* PIOS_INCLUDE_USB */
|
||||
|
||||
// Receive from USB HID if available, otherwise UAVTalk com if it's available.
|
||||
if (params->isGCS && HID_available)
|
||||
BufferedReadSetCom(f, PIOS_COM_USB_HID);
|
||||
else
|
||||
{
|
||||
if (params->comPort)
|
||||
BufferedReadSetCom(f, params->comPort);
|
||||
else
|
||||
{
|
||||
vTaskDelay(5);
|
||||
continue;
|
||||
}
|
||||
}
|
||||
|
||||
// Send packets to the UAVTalk port if this is a GCS connction and UAVTalk port is configured
|
||||
// or to the GCS port if this is a UAVTalk connection and USB is plugged in.
|
||||
if ((params->isGCS && data->UAVTalkCon) || (!params->isGCS && HID_available))
|
||||
sendQueue = params->sendQueue;
|
||||
|
||||
// Read the next byte
|
||||
uint8_t rx_byte;
|
||||
if (!BufferedRead(f, &rx_byte, MAX_PORT_DELAY))
|
||||
continue;
|
||||
|
||||
// Get a TX packet from the packet handler if required.
|
||||
if (p == NULL)
|
||||
{
|
||||
|
||||
// Wait until we receive a sync.
|
||||
UAVTalkRxState state = UAVTalkProcessInputStreamQuiet(params->UAVTalkCon, rx_byte);
|
||||
if (state != UAVTALK_STATE_TYPE)
|
||||
continue;
|
||||
|
||||
// Get a packet when we see the sync
|
||||
p = PHGetTXPacket(pios_packet_handler);
|
||||
|
||||
// No packets available?
|
||||
if (p == NULL)
|
||||
{
|
||||
data->droppedPackets++;
|
||||
continue;
|
||||
}
|
||||
|
||||
// Initialize the packet.
|
||||
p->header.destination_id = data->destination_id;
|
||||
p->header.type = PACKET_TYPE_DATA;
|
||||
p->data[0] = rx_byte;
|
||||
p->header.data_size = 1;
|
||||
continue;
|
||||
}
|
||||
|
||||
// Insert this byte.
|
||||
p->data[p->header.data_size++] = rx_byte;
|
||||
|
||||
// Keep reading until we receive a completed packet.
|
||||
UAVTalkRxState state = UAVTalkProcessInputStreamQuiet(params->UAVTalkCon, rx_byte);
|
||||
UAVTalkConnectionData *connection = (UAVTalkConnectionData*)(params->UAVTalkCon);
|
||||
UAVTalkInputProcessor *iproc = &(connection->iproc);
|
||||
|
||||
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 == PIPXSETTINGS_OBJID)
|
||||
{
|
||||
// Queue up the ACK.
|
||||
queueEvent(params->recvQueue, (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_EEPROM)
|
||||
// Load the settings.
|
||||
PipXSettingsData pipxSettings;
|
||||
if (PIOS_EEPROM_Load((uint8_t*)&pipxSettings, sizeof(PipXSettingsData)) == 0)
|
||||
PipXSettingsSet(&pipxSettings);
|
||||
else
|
||||
success = false;
|
||||
#endif
|
||||
break;
|
||||
}
|
||||
case OBJECTPERSISTENCE_OPERATION_SAVE:
|
||||
{
|
||||
#if defined(PIOS_INCLUDE_FLASH_EEPROM)
|
||||
// Save the settings.
|
||||
PipXSettingsData pipxSettings;
|
||||
PipXSettingsGet(&pipxSettings);
|
||||
int32_t ret = PIOS_EEPROM_Save((uint8_t*)&pipxSettings, sizeof(PipXSettingsData));
|
||||
if (ret != 0)
|
||||
success = false;
|
||||
#endif
|
||||
break;
|
||||
}
|
||||
case OBJECTPERSISTENCE_OPERATION_DELETE:
|
||||
{
|
||||
#if defined(PIOS_INCLUDE_FLASH_EEPROM)
|
||||
// Erase the settings.
|
||||
PipXSettingsData pipxSettings;
|
||||
uint8_t *ptr = (uint8_t*)&pipxSettings;
|
||||
memset(ptr, 0, sizeof(PipXSettingsData));
|
||||
int32_t ret = PIOS_EEPROM_Save(ptr, sizeof(PipXSettingsData));
|
||||
if (ret != 0)
|
||||
success = false;
|
||||
#endif
|
||||
break;
|
||||
}
|
||||
default:
|
||||
break;
|
||||
}
|
||||
if (success == true)
|
||||
{
|
||||
obj_per.Operation = OBJECTPERSISTENCE_OPERATION_COMPLETED;
|
||||
ObjectPersistenceSet(&obj_per);
|
||||
}
|
||||
|
||||
// Release the packet, since we don't need it.
|
||||
PHReleaseTXPacket(pios_packet_handler, p);
|
||||
}
|
||||
else
|
||||
{
|
||||
// Otherwise, queue the packet for transmission.
|
||||
if (sendQueue)
|
||||
queueEvent(sendQueue, (void*)p, 0, EV_TRANSMIT_PACKET);
|
||||
else
|
||||
PHTransmitPacket(PIOS_PACKET_HANDLER, p);
|
||||
}
|
||||
}
|
||||
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(params->recvQueue, (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(params->recvQueue, (void*)iproc->obj, iproc->instId, EV_SEND_ACK);
|
||||
break;
|
||||
}
|
||||
|
||||
// Release the packet, since we don't need it.
|
||||
PHReleaseTXPacket(pios_packet_handler, p);
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
// Queue the packet for transmission.
|
||||
if (sendQueue)
|
||||
queueEvent(sendQueue, (void*)p, 0, EV_TRANSMIT_PACKET);
|
||||
else
|
||||
PHTransmitPacket(PIOS_PACKET_HANDLER, p);
|
||||
}
|
||||
p = NULL;
|
||||
|
||||
} else if(state == UAVTALK_STATE_ERROR) {
|
||||
data->UAVTalkErrors++;
|
||||
|
||||
// Send a NACK if required.
|
||||
if((iproc->obj) && (iproc->type == UAVTALK_TYPE_OBJ_ACK))
|
||||
{
|
||||
// Queue up a NACK
|
||||
queueEvent(params->recvQueue, iproc->obj, iproc->instId, EV_SEND_NACK);
|
||||
|
||||
// Release the packet and start over again.
|
||||
PHReleaseTXPacket(pios_packet_handler, p);
|
||||
}
|
||||
else
|
||||
{
|
||||
// Transmit the packet anyway...
|
||||
if (sendQueue)
|
||||
queueEvent(sendQueue, (void*)p, 0, EV_TRANSMIT_PACKET);
|
||||
else
|
||||
PHTransmitPacket(PIOS_PACKET_HANDLER, p);
|
||||
}
|
||||
p = NULL;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Send packets to the com port.
|
||||
*/
|
||||
static void UAVTalkSendTask(void *parameters)
|
||||
{
|
||||
UAVTalkComTaskParams *params = (UAVTalkComTaskParams *)parameters;
|
||||
UAVObjEvent ev;
|
||||
|
||||
// Loop forever
|
||||
while (1) {
|
||||
#ifdef PIOS_INCLUDE_WDG
|
||||
// Update the watchdog timer.
|
||||
// NOTE: this is temporarily turned off becase PIOS_Com_SendBuffer appears to block for an uncontrollable time,
|
||||
// and SendBufferNonBlocking doesn't seem to be working in this case.
|
||||
//PIOS_WDG_UpdateFlag(PIOS_WDG_SENDDATA);
|
||||
#endif /* PIOS_INCLUDE_WDG */
|
||||
// Wait for a packet on the queue.
|
||||
if (xQueueReceive(params->recvQueue, &ev, MAX_PORT_DELAY) == pdTRUE) {
|
||||
PIOS_WDG_UpdateFlag(PIOS_WDG_TELEMETRY);
|
||||
#endif
|
||||
// Wait for queue message
|
||||
if (xQueueReceive(data->uavtalkEventQueue, &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(params->UAVTalkCon, ev.obj, 0, 0, RETRY_TIMEOUT_MS) == 0;
|
||||
success = UAVTalkSendObject(data->outUAVTalkCon, ev.obj, 0, 0, RETRY_TIMEOUT_MS) == 0;
|
||||
if (!success)
|
||||
++retries;
|
||||
}
|
||||
@ -527,7 +205,7 @@ static void UAVTalkSendTask(void *parameters)
|
||||
uint32_t retries = 0;
|
||||
int32_t success = -1;
|
||||
while (retries < MAX_RETRIES && success == -1) {
|
||||
success = UAVTalkSendAck(params->UAVTalkCon, ev.obj, ev.instId) == 0;
|
||||
success = UAVTalkSendAck(data->outUAVTalkCon, ev.obj, ev.instId) == 0;
|
||||
if (!success)
|
||||
++retries;
|
||||
}
|
||||
@ -539,182 +217,76 @@ static void UAVTalkSendTask(void *parameters)
|
||||
uint32_t retries = 0;
|
||||
int32_t success = -1;
|
||||
while (retries < MAX_RETRIES && success == -1) {
|
||||
success = UAVTalkSendNack(params->UAVTalkCon, UAVObjGetID(ev.obj)) == 0;
|
||||
success = UAVTalkSendNack(data->outUAVTalkCon, UAVObjGetID(ev.obj)) == 0;
|
||||
if (!success)
|
||||
++retries;
|
||||
}
|
||||
data->comTxRetries += retries;
|
||||
}
|
||||
else if(ev.event == EV_PACKET_RECEIVED)
|
||||
{
|
||||
// Receive the packet.
|
||||
PHReceivePacket(pios_packet_handler, (PHPacketHandle)ev.obj);
|
||||
}
|
||||
else if(ev.event == EV_TRANSMIT_PACKET)
|
||||
{
|
||||
// Transmit the packet.
|
||||
PHPacketHandle p = (PHPacketHandle)ev.obj;
|
||||
UAVTalkSendBuf(params->UAVTalkCon, p->data, p->header.data_size);
|
||||
PHReleaseTXPacket(pios_packet_handler, p);
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* The com to radio bridge task.
|
||||
* Radio rx task. Receive data packets from the radio and pass them on.
|
||||
*/
|
||||
static void transparentCommTask(void * parameters)
|
||||
static void radioRxTask(void *parameters)
|
||||
{
|
||||
portTickType packet_start_time = 0;
|
||||
uint32_t timeout = MAX_PORT_DELAY;
|
||||
PHPacketHandle p = NULL;
|
||||
|
||||
/* Handle usart/usb -> radio direction */
|
||||
// Task loop
|
||||
while (1) {
|
||||
|
||||
#ifdef PIOS_INCLUDE_WDG
|
||||
// Update the watchdog timer.
|
||||
PIOS_WDG_UpdateFlag(PIOS_WDG_TRANSCOMM);
|
||||
#endif /* PIOS_INCLUDE_WDG */
|
||||
|
||||
// Get a TX packet from the packet handler if required.
|
||||
if (p == NULL)
|
||||
{
|
||||
p = PHGetTXPacket(pios_packet_handler);
|
||||
|
||||
// No packets available?
|
||||
if (p == NULL)
|
||||
{
|
||||
data->droppedPackets++;
|
||||
// Wait a bit for a packet to come available.
|
||||
vTaskDelay(5);
|
||||
continue;
|
||||
}
|
||||
|
||||
// Initialize the packet.
|
||||
p->header.destination_id = data->destination_id;
|
||||
//p->header.type = PACKET_TYPE_ACKED_DATA;
|
||||
p->header.type = PACKET_TYPE_DATA;
|
||||
p->header.data_size = 0;
|
||||
}
|
||||
|
||||
// Receive data from the com port
|
||||
uint32_t cur_rx_bytes = PIOS_COM_ReceiveBuffer(PIOS_COM_TRANS_COM, p->data + p->header.data_size,
|
||||
PH_MAX_DATA - p->header.data_size, timeout);
|
||||
|
||||
// Do we have an data to send?
|
||||
p->header.data_size += cur_rx_bytes;
|
||||
if (p->header.data_size > 0) {
|
||||
|
||||
// Check how long since last update
|
||||
portTickType cur_sys_time = xTaskGetTickCount();
|
||||
|
||||
// Is this the start of a packet?
|
||||
if(packet_start_time == 0)
|
||||
packet_start_time = cur_sys_time;
|
||||
|
||||
// Just send the packet on wraparound
|
||||
bool send_packet = (cur_sys_time < packet_start_time);
|
||||
if (!send_packet)
|
||||
{
|
||||
portTickType dT = (cur_sys_time - packet_start_time) / portTICK_RATE_MS;
|
||||
if (dT > data->send_timeout)
|
||||
send_packet = true;
|
||||
else
|
||||
timeout = data->send_timeout - dT;
|
||||
}
|
||||
|
||||
// Also send the packet if the size is over the minimum.
|
||||
send_packet |= (p->header.data_size > data->min_packet_size);
|
||||
|
||||
// Should we send this packet?
|
||||
if (send_packet)
|
||||
{
|
||||
// Queue the packet for transmission.
|
||||
PHTransmitPacket(PIOS_PACKET_HANDLER, p);
|
||||
|
||||
// Reset the timeout
|
||||
timeout = MAX_PORT_DELAY;
|
||||
p = NULL;
|
||||
packet_start_time = 0;
|
||||
}
|
||||
}
|
||||
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)
|
||||
for (uint8_t i = 0; i < bytes_to_process; i++)
|
||||
if (UAVTalkRelayInputStream(data->outUAVTalkCon, serial_data[i]) == UAVTALK_STATE_ERROR)
|
||||
data->UAVTalkErrors++;
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* The PPM input task.
|
||||
* Radio rx task. Receive data from a com port and pass it on to the radio.
|
||||
*/
|
||||
static void ppmInputTask(void *parameters)
|
||||
static void radioTxTask(void *parameters)
|
||||
{
|
||||
PHPpmPacket ppm_packet;
|
||||
PHPacketHandle pph = (PHPacketHandle)&ppm_packet;
|
||||
|
||||
// Task loop
|
||||
while (1) {
|
||||
|
||||
uint32_t inputPort = PIOS_COM_TELEMETRY;
|
||||
#ifdef PIOS_INCLUDE_WDG
|
||||
// Update the watchdog timer.
|
||||
PIOS_WDG_UpdateFlag(PIOS_WDG_PPMINPUT);
|
||||
#endif /* PIOS_INCLUDE_WDG */
|
||||
|
||||
// Read the receiver.
|
||||
bool valid_input_detected = false;
|
||||
for (uint8_t i = 1; i <= PIOS_PPM_NUM_INPUTS; ++i)
|
||||
PIOS_WDG_UpdateFlag(PIOS_WDG_RADIOTX);
|
||||
#endif
|
||||
#if defined(PIOS_INCLUDE_USB)
|
||||
// Determine output port (USB takes priority over telemetry port)
|
||||
if (PIOS_USB_CheckAvailable(0) && PIOS_COM_TELEM_USB)
|
||||
inputPort = PIOS_COM_TELEM_USB;
|
||||
#endif /* PIOS_INCLUDE_USB */
|
||||
if(inputPort)
|
||||
{
|
||||
ppm_packet.channels[i - 1] = PIOS_RCVR_Read(PIOS_PPM_RECEIVER, i);
|
||||
if(ppm_packet.channels[i - 1] != PIOS_RCVR_TIMEOUT)
|
||||
valid_input_detected = true;
|
||||
uint8_t serial_data[1];
|
||||
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]);
|
||||
}
|
||||
|
||||
// Send the PPM packet if it's valid
|
||||
if (valid_input_detected)
|
||||
{
|
||||
// Set the GCSReceiver UAVO if we're connected to the FC.
|
||||
if (data->UAVTalkCon)
|
||||
{
|
||||
GCSReceiverData rcvr;
|
||||
|
||||
// Copy the receiver channels into the GCSReceiver object.
|
||||
for (uint8_t i = 0; i < GCSRECEIVER_CHANNEL_NUMELEM; ++i)
|
||||
rcvr.Channel[i] = ppm_packet.channels[i];
|
||||
|
||||
// Set the GCSReceiverData object.
|
||||
GCSReceiverSet(&rcvr);
|
||||
}
|
||||
else
|
||||
{
|
||||
// Otherwise, send a PPM packet over the radio link.
|
||||
ppm_packet.header.destination_id = data->destination_id;
|
||||
ppm_packet.header.type = PACKET_TYPE_PPM;
|
||||
ppm_packet.header.data_size = PH_PPM_DATA_SIZE(&ppm_packet);
|
||||
PHTransmitPacket(PIOS_PACKET_HANDLER, pph);
|
||||
}
|
||||
}
|
||||
|
||||
// Delay until the next update period.
|
||||
vTaskDelay(PIOS_PPM_PACKET_UPDATE_PERIOD_MS / portTICK_RATE_MS);
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Transmit data buffer to the com port.
|
||||
* \param[in] params The comm parameters.
|
||||
* \param[in] buf Data buffer to send
|
||||
* \param[in] length Length of buffer
|
||||
* \return -1 on failure
|
||||
* \return number of bytes transmitted on success
|
||||
*/
|
||||
static int32_t UAVTalkSend(UAVTalkComTaskParams *params, uint8_t *buf, int32_t length)
|
||||
static int32_t UAVTalkSendHandler(uint8_t *buf, int32_t length)
|
||||
{
|
||||
uint32_t outputPort = params->comPort;
|
||||
uint32_t outputPort = PIOS_COM_TELEMETRY;
|
||||
#if defined(PIOS_INCLUDE_USB)
|
||||
if (params->isGCS)
|
||||
{
|
||||
// Determine output port (USB takes priority over telemetry port)
|
||||
if (PIOS_USB_CheckAvailable(0) && PIOS_COM_USB_HID)
|
||||
outputPort = PIOS_COM_USB_HID;
|
||||
}
|
||||
// Determine output port (USB takes priority over telemetry port)
|
||||
if (PIOS_COM_TELEM_USB && PIOS_COM_Available(PIOS_COM_TELEM_USB))
|
||||
outputPort = PIOS_COM_TELEM_USB;
|
||||
#endif /* PIOS_INCLUDE_USB */
|
||||
if(outputPort)
|
||||
return PIOS_COM_SendBufferNonBlocking(outputPort, buf, length);
|
||||
@ -729,103 +301,126 @@ static int32_t UAVTalkSend(UAVTalkComTaskParams *params, uint8_t *buf, int32_t l
|
||||
* \return -1 on failure
|
||||
* \return number of bytes transmitted on success
|
||||
*/
|
||||
static int32_t UAVTalkSendHandler(uint8_t *buf, int32_t length)
|
||||
static int32_t RadioSendHandler(uint8_t *buf, int32_t length)
|
||||
{
|
||||
return UAVTalkSend(&(data->uavtalk_params), buf, length);
|
||||
}
|
||||
|
||||
/**
|
||||
* Transmit data buffer to the com port.
|
||||
* \param[in] buf Data buffer to send
|
||||
* \param[in] length Length of buffer
|
||||
* \return -1 on failure
|
||||
* \return number of bytes transmitted on success
|
||||
*/
|
||||
static int32_t GCSUAVTalkSendHandler(uint8_t *buf, int32_t length)
|
||||
{
|
||||
return UAVTalkSend(&(data->gcs_uavtalk_params), buf, length);
|
||||
}
|
||||
|
||||
/**
|
||||
* Receive a packet
|
||||
* \param[in] buf The received data buffer
|
||||
* \param[in] length Length of buffer
|
||||
*/
|
||||
static void transmitData(uint32_t outputPort, uint8_t *buf, uint8_t len, bool checkHid)
|
||||
{
|
||||
#if defined(PIOS_INCLUDE_USB)
|
||||
// See if USB is connected if requested.
|
||||
if(checkHid)
|
||||
// Determine output port (USB takes priority over telemetry port)
|
||||
if (PIOS_USB_CheckAvailable(0) && PIOS_COM_USB_HID)
|
||||
outputPort = PIOS_COM_USB_HID;
|
||||
#endif /* PIOS_INCLUDE_USB */
|
||||
if (!outputPort)
|
||||
return;
|
||||
|
||||
// Send the received data to the com port
|
||||
if (PIOS_COM_SendBuffer(outputPort, buf, len) != len)
|
||||
// Error on transmit
|
||||
data->comTxErrors++;
|
||||
}
|
||||
|
||||
/**
|
||||
* Receive a packet
|
||||
* \param[in] buf The received data buffer
|
||||
* \param[in] length Length of buffer
|
||||
*/
|
||||
static void receiveData(uint8_t *buf, uint8_t len, int8_t rssi, int8_t afc)
|
||||
{
|
||||
data->RSSI = rssi;
|
||||
|
||||
// Packet data should go to transparent com if it's configured,
|
||||
// or just send it through the UAVTalk link.
|
||||
if (PIOS_COM_TRANS_COM)
|
||||
transmitData(PIOS_COM_TRANS_COM, buf, len, false);
|
||||
else if (data->UAVTalkCon)
|
||||
UAVTalkSendBuf(data->UAVTalkCon, buf, len);
|
||||
uint32_t outputPort = PIOS_COM_RADIO;
|
||||
// Don't send any data unless the radio port is available.
|
||||
if(outputPort && PIOS_COM_Available(outputPort))
|
||||
return PIOS_COM_SendBuffer(outputPort, buf, length);
|
||||
else
|
||||
UAVTalkSendBuf(data->GCSUAVTalkCon, buf, len);
|
||||
// For some reason, if this function returns failure, it prevents saving settings.
|
||||
return length;
|
||||
}
|
||||
|
||||
static BufferedReadHandle BufferedReadInit(uint32_t com_port, uint16_t buffer_length)
|
||||
static void ProcessInputStream(UAVTalkConnection connectionHandle, uint8_t rxbyte)
|
||||
{
|
||||
BufferedReadHandle h = (BufferedReadHandle)pvPortMalloc(sizeof(ReadBuffer));
|
||||
if (!h)
|
||||
return NULL;
|
||||
// Keep reading until we receive a completed packet.
|
||||
UAVTalkRxState state = UAVTalkRelayInputStream(connectionHandle, rxbyte);
|
||||
UAVTalkConnectionData *connection = (UAVTalkConnectionData*)(connectionHandle);
|
||||
UAVTalkInputProcessor *iproc = &(connection->iproc);
|
||||
|
||||
h->com_port = com_port;
|
||||
h->buffer = (uint8_t*)pvPortMalloc(buffer_length);
|
||||
h->length = buffer_length;
|
||||
h->index = 0;
|
||||
h->data_length = 0;
|
||||
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);
|
||||
|
||||
if (h->buffer == NULL)
|
||||
return NULL;
|
||||
// Get the ObjectPersistence object.
|
||||
ObjectPersistenceData obj_per;
|
||||
ObjectPersistenceGet(&obj_per);
|
||||
|
||||
return h;
|
||||
}
|
||||
// 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);
|
||||
|
||||
static bool BufferedRead(BufferedReadHandle h, uint8_t *value, uint32_t timeout_ms)
|
||||
{
|
||||
// Read some data if required.
|
||||
if(h->index == h->data_length)
|
||||
{
|
||||
uint32_t rx_bytes = PIOS_COM_ReceiveBuffer(h->com_port, h->buffer, h->length, timeout_ms);
|
||||
if (rx_bytes == 0)
|
||||
return false;
|
||||
h->index = 0;
|
||||
h->data_length = rx_bytes;
|
||||
}
|
||||
// Is this a save, load, or delete?
|
||||
bool success = true;
|
||||
switch (obj_per.Operation)
|
||||
{
|
||||
case OBJECTPERSISTENCE_OPERATION_LOAD:
|
||||
{
|
||||
#if defined(PIOS_INCLUDE_FLASH_EEPROM)
|
||||
// Load the settings.
|
||||
OPLinkSettingsData oplinkSettings;
|
||||
if (PIOS_EEPROM_Load((uint8_t*)&oplinkSettings, sizeof(OPLinkSettingsData)) == 0)
|
||||
OPLinkSettingsSet(&oplinkSettings);
|
||||
else
|
||||
success = false;
|
||||
#endif
|
||||
break;
|
||||
}
|
||||
case OBJECTPERSISTENCE_OPERATION_SAVE:
|
||||
{
|
||||
#if defined(PIOS_INCLUDE_FLASH_EEPROM)
|
||||
// Save the settings.
|
||||
OPLinkSettingsData oplinkSettings;
|
||||
OPLinkSettingsGet(&oplinkSettings);
|
||||
int32_t ret = PIOS_EEPROM_Save((uint8_t*)&oplinkSettings, sizeof(OPLinkSettingsData));
|
||||
if (ret != 0)
|
||||
success = false;
|
||||
#endif
|
||||
break;
|
||||
}
|
||||
case OBJECTPERSISTENCE_OPERATION_DELETE:
|
||||
{
|
||||
#if defined(PIOS_INCLUDE_FLASH_EEPROM)
|
||||
// Erase the settings.
|
||||
OPLinkSettingsData oplinkSettings;
|
||||
uint8_t *ptr = (uint8_t*)&oplinkSettings;
|
||||
memset(ptr, 0, sizeof(OPLinkSettingsData));
|
||||
int32_t ret = PIOS_EEPROM_Save(ptr, sizeof(OPLinkSettingsData));
|
||||
if (ret != 0)
|
||||
success = false;
|
||||
#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;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// Return the next byte.
|
||||
*value = h->buffer[h->index++];
|
||||
return true;
|
||||
}
|
||||
} else if(state == UAVTALK_STATE_ERROR) {
|
||||
data->UAVTalkErrors++;
|
||||
|
||||
static void BufferedReadSetCom(BufferedReadHandle h, uint32_t com_port)
|
||||
{
|
||||
h->com_port = com_port;
|
||||
// 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);
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
@ -844,95 +439,165 @@ static void queueEvent(xQueueHandle queue, void *obj, uint16_t instId, UAVObjEve
|
||||
}
|
||||
|
||||
/**
|
||||
* Update the telemetry settings, called on startup.
|
||||
* FIXME: This should be in the TelemetrySettings object. But objects
|
||||
* have too much overhead yet. Also the telemetry has no any specific
|
||||
* settings, etc. Thus the HwSettings object which contains the
|
||||
* telemetry port speed is used for now.
|
||||
* 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(OPLinkSettingsOutputConnectionOptions com_port, OPLinkSettingsComSpeedOptions com_speed)
|
||||
{
|
||||
|
||||
// Get the settings.
|
||||
OPLinkSettingsData oplinkSettings;
|
||||
OPLinkSettingsGet(&oplinkSettings);
|
||||
|
||||
// Set the output telemetry port and speed.
|
||||
switch (com_port)
|
||||
{
|
||||
case OPLINKSETTINGS_OUTPUTCONNECTION_REMOTEHID:
|
||||
oplinkSettings.InputConnection = OPLINKSETTINGS_INPUTCONNECTION_HID;
|
||||
break;
|
||||
case OPLINKSETTINGS_OUTPUTCONNECTION_REMOTEVCP:
|
||||
oplinkSettings.InputConnection = OPLINKSETTINGS_INPUTCONNECTION_VCP;
|
||||
break;
|
||||
case OPLINKSETTINGS_OUTPUTCONNECTION_REMOTETELEMETRY:
|
||||
oplinkSettings.InputConnection = OPLINKSETTINGS_INPUTCONNECTION_TELEMETRY;
|
||||
break;
|
||||
case OPLINKSETTINGS_OUTPUTCONNECTION_REMOTEFLEXI:
|
||||
oplinkSettings.InputConnection = OPLINKSETTINGS_INPUTCONNECTION_FLEXI;
|
||||
break;
|
||||
case OPLINKSETTINGS_OUTPUTCONNECTION_TELEMETRY:
|
||||
oplinkSettings.InputConnection = OPLINKSETTINGS_INPUTCONNECTION_HID;
|
||||
break;
|
||||
case OPLINKSETTINGS_OUTPUTCONNECTION_FLEXI:
|
||||
oplinkSettings.InputConnection = OPLINKSETTINGS_INPUTCONNECTION_HID;
|
||||
break;
|
||||
}
|
||||
oplinkSettings.ComSpeed = com_speed;
|
||||
|
||||
// A non-coordinator modem should not set a remote telemetry connection.
|
||||
oplinkSettings.OutputConnection = OPLINKSETTINGS_OUTPUTCONNECTION_REMOTEHID;
|
||||
|
||||
// Update the OPLinkSettings object.
|
||||
OPLinkSettingsSet(&oplinkSettings);
|
||||
|
||||
// Perform the update.
|
||||
updateSettings();
|
||||
}
|
||||
|
||||
/**
|
||||
* Update the oplink settings, called on startup.
|
||||
*/
|
||||
static void updateSettings()
|
||||
{
|
||||
|
||||
// Get the settings.
|
||||
PipXSettingsData pipxSettings;
|
||||
PipXSettingsGet(&pipxSettings);
|
||||
OPLinkSettingsData oplinkSettings;
|
||||
OPLinkSettingsGet(&oplinkSettings);
|
||||
|
||||
// Initialize the destination ID
|
||||
data->destination_id = pipxSettings.PairID ? pipxSettings.PairID : 0xffffffff;
|
||||
|
||||
if (PIOS_COM_TELEMETRY) {
|
||||
switch (pipxSettings.TelemetrySpeed) {
|
||||
case PIPXSETTINGS_TELEMETRYSPEED_2400:
|
||||
PIOS_COM_ChangeBaud(PIOS_COM_TELEMETRY, 2400);
|
||||
bool is_coordinator = (oplinkSettings.Coordinator == OPLINKSETTINGS_COORDINATOR_TRUE);
|
||||
if (is_coordinator)
|
||||
{
|
||||
// Set the remote com configuration parameters
|
||||
PIOS_RFM22B_SetRemoteComConfig(pios_rfm22b_id, oplinkSettings.OutputConnection, oplinkSettings.ComSpeed);
|
||||
|
||||
// Configure the RFM22B device as coordinator or not
|
||||
PIOS_RFM22B_SetCoordinator(pios_rfm22b_id, true);
|
||||
|
||||
// Set the frequencies.
|
||||
PIOS_RFM22B_SetFrequencyRange(pios_rfm22b_id, oplinkSettings.MinFrequency, oplinkSettings.MaxFrequency);
|
||||
|
||||
// Set the maximum radio RF power.
|
||||
switch (oplinkSettings.MaxRFPower)
|
||||
{
|
||||
case OPLINKSETTINGS_MAXRFPOWER_125:
|
||||
PIOS_RFM22B_SetTxPower(pios_rfm22b_id, RFM22_tx_pwr_txpow_0);
|
||||
break;
|
||||
case PIPXSETTINGS_TELEMETRYSPEED_4800:
|
||||
PIOS_COM_ChangeBaud(PIOS_COM_TELEMETRY, 4800);
|
||||
case OPLINKSETTINGS_MAXRFPOWER_16:
|
||||
PIOS_RFM22B_SetTxPower(pios_rfm22b_id, RFM22_tx_pwr_txpow_1);
|
||||
break;
|
||||
case PIPXSETTINGS_TELEMETRYSPEED_9600:
|
||||
PIOS_COM_ChangeBaud(PIOS_COM_TELEMETRY, 9600);
|
||||
case OPLINKSETTINGS_MAXRFPOWER_316:
|
||||
PIOS_RFM22B_SetTxPower(pios_rfm22b_id, RFM22_tx_pwr_txpow_2);
|
||||
break;
|
||||
case PIPXSETTINGS_TELEMETRYSPEED_19200:
|
||||
PIOS_COM_ChangeBaud(PIOS_COM_TELEMETRY, 19200);
|
||||
case OPLINKSETTINGS_MAXRFPOWER_63:
|
||||
PIOS_RFM22B_SetTxPower(pios_rfm22b_id, RFM22_tx_pwr_txpow_3);
|
||||
break;
|
||||
case PIPXSETTINGS_TELEMETRYSPEED_38400:
|
||||
PIOS_COM_ChangeBaud(PIOS_COM_TELEMETRY, 38400);
|
||||
case OPLINKSETTINGS_MAXRFPOWER_126:
|
||||
PIOS_RFM22B_SetTxPower(pios_rfm22b_id, RFM22_tx_pwr_txpow_4);
|
||||
break;
|
||||
case PIPXSETTINGS_TELEMETRYSPEED_57600:
|
||||
PIOS_COM_ChangeBaud(PIOS_COM_TELEMETRY, 57600);
|
||||
case OPLINKSETTINGS_MAXRFPOWER_25:
|
||||
PIOS_RFM22B_SetTxPower(pios_rfm22b_id, RFM22_tx_pwr_txpow_5);
|
||||
break;
|
||||
case PIPXSETTINGS_TELEMETRYSPEED_115200:
|
||||
PIOS_COM_ChangeBaud(PIOS_COM_TELEMETRY, 115200);
|
||||
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;
|
||||
}
|
||||
|
||||
// Set the radio destination ID.
|
||||
PIOS_RFM22B_SetDestinationId(pios_rfm22b_id, oplinkSettings.PairID);
|
||||
}
|
||||
if (PIOS_COM_FLEXI) {
|
||||
switch (pipxSettings.FlexiSpeed) {
|
||||
case PIPXSETTINGS_TELEMETRYSPEED_2400:
|
||||
PIOS_COM_ChangeBaud(PIOS_COM_FLEXI, 2400);
|
||||
break;
|
||||
case PIPXSETTINGS_TELEMETRYSPEED_4800:
|
||||
PIOS_COM_ChangeBaud(PIOS_COM_FLEXI, 4800);
|
||||
break;
|
||||
case PIPXSETTINGS_TELEMETRYSPEED_9600:
|
||||
PIOS_COM_ChangeBaud(PIOS_COM_FLEXI, 9600);
|
||||
break;
|
||||
case PIPXSETTINGS_TELEMETRYSPEED_19200:
|
||||
PIOS_COM_ChangeBaud(PIOS_COM_FLEXI, 19200);
|
||||
break;
|
||||
case PIPXSETTINGS_TELEMETRYSPEED_38400:
|
||||
PIOS_COM_ChangeBaud(PIOS_COM_FLEXI, 38400);
|
||||
break;
|
||||
case PIPXSETTINGS_TELEMETRYSPEED_57600:
|
||||
PIOS_COM_ChangeBaud(PIOS_COM_FLEXI, 57600);
|
||||
break;
|
||||
case PIPXSETTINGS_TELEMETRYSPEED_115200:
|
||||
PIOS_COM_ChangeBaud(PIOS_COM_FLEXI, 115200);
|
||||
break;
|
||||
}
|
||||
|
||||
// Determine what com ports we're using.
|
||||
switch (oplinkSettings.InputConnection)
|
||||
{
|
||||
case OPLINKSETTINGS_INPUTCONNECTION_VCP:
|
||||
PIOS_COM_TELEMETRY = PIOS_COM_TELEM_VCP;
|
||||
break;
|
||||
case OPLINKSETTINGS_INPUTCONNECTION_TELEMETRY:
|
||||
PIOS_COM_TELEMETRY = PIOS_COM_TELEM_UART_TELEM;
|
||||
break;
|
||||
case OPLINKSETTINGS_INPUTCONNECTION_FLEXI:
|
||||
PIOS_COM_TELEMETRY = PIOS_COM_TELEM_UART_FLEXI;
|
||||
break;
|
||||
default:
|
||||
PIOS_COM_TELEMETRY = 0;
|
||||
break;
|
||||
}
|
||||
if (PIOS_COM_VCP) {
|
||||
switch (pipxSettings.VCPSpeed) {
|
||||
case PIPXSETTINGS_TELEMETRYSPEED_2400:
|
||||
PIOS_COM_ChangeBaud(PIOS_COM_VCP, 2400);
|
||||
break;
|
||||
case PIPXSETTINGS_TELEMETRYSPEED_4800:
|
||||
PIOS_COM_ChangeBaud(PIOS_COM_VCP, 4800);
|
||||
break;
|
||||
case PIPXSETTINGS_TELEMETRYSPEED_9600:
|
||||
PIOS_COM_ChangeBaud(PIOS_COM_VCP, 9600);
|
||||
break;
|
||||
case PIPXSETTINGS_TELEMETRYSPEED_19200:
|
||||
PIOS_COM_ChangeBaud(PIOS_COM_VCP, 19200);
|
||||
break;
|
||||
case PIPXSETTINGS_TELEMETRYSPEED_38400:
|
||||
PIOS_COM_ChangeBaud(PIOS_COM_VCP, 38400);
|
||||
break;
|
||||
case PIPXSETTINGS_TELEMETRYSPEED_57600:
|
||||
PIOS_COM_ChangeBaud(PIOS_COM_VCP, 57600);
|
||||
break;
|
||||
case PIPXSETTINGS_TELEMETRYSPEED_115200:
|
||||
PIOS_COM_ChangeBaud(PIOS_COM_VCP, 115200);
|
||||
break;
|
||||
}
|
||||
|
||||
switch (oplinkSettings.OutputConnection)
|
||||
{
|
||||
case OPLINKSETTINGS_OUTPUTCONNECTION_FLEXI:
|
||||
PIOS_COM_RADIO = PIOS_COM_TELEM_UART_FLEXI;
|
||||
break;
|
||||
case OPLINKSETTINGS_OUTPUTCONNECTION_TELEMETRY:
|
||||
PIOS_COM_RADIO = PIOS_COM_TELEM_UART_TELEM;
|
||||
break;
|
||||
default:
|
||||
PIOS_COM_RADIO = PIOS_COM_RFM22B;
|
||||
break;
|
||||
}
|
||||
|
||||
// Configure the com port speeds.
|
||||
switch (oplinkSettings.ComSpeed) {
|
||||
case OPLINKSETTINGS_COMSPEED_2400:
|
||||
if (is_coordinator && PIOS_COM_RADIO) PIOS_COM_ChangeBaud(PIOS_COM_RADIO, 2400);
|
||||
if (PIOS_COM_TELEMETRY) PIOS_COM_ChangeBaud(PIOS_COM_TELEMETRY, 2400);
|
||||
break;
|
||||
case OPLINKSETTINGS_COMSPEED_4800:
|
||||
if (is_coordinator && PIOS_COM_RADIO) PIOS_COM_ChangeBaud(PIOS_COM_RADIO, 4800);
|
||||
if (PIOS_COM_TELEMETRY) PIOS_COM_ChangeBaud(PIOS_COM_TELEMETRY, 4800);
|
||||
break;
|
||||
case OPLINKSETTINGS_COMSPEED_9600:
|
||||
if (is_coordinator && PIOS_COM_RADIO) PIOS_COM_ChangeBaud(PIOS_COM_RADIO, 9600);
|
||||
if (PIOS_COM_TELEMETRY) PIOS_COM_ChangeBaud(PIOS_COM_TELEMETRY, 9600);
|
||||
break;
|
||||
case OPLINKSETTINGS_COMSPEED_19200:
|
||||
if (is_coordinator && PIOS_COM_RADIO) PIOS_COM_ChangeBaud(PIOS_COM_RADIO, 19200);
|
||||
if (PIOS_COM_TELEMETRY) PIOS_COM_ChangeBaud(PIOS_COM_TELEMETRY, 19200);
|
||||
break;
|
||||
case OPLINKSETTINGS_COMSPEED_38400:
|
||||
if (is_coordinator && PIOS_COM_RADIO) PIOS_COM_ChangeBaud(PIOS_COM_RADIO, 38400);
|
||||
if (PIOS_COM_TELEMETRY) PIOS_COM_ChangeBaud(PIOS_COM_TELEMETRY, 38400);
|
||||
break;
|
||||
case OPLINKSETTINGS_COMSPEED_57600:
|
||||
if (is_coordinator && PIOS_COM_RADIO) PIOS_COM_ChangeBaud(PIOS_COM_RADIO, 57600);
|
||||
if (PIOS_COM_TELEMETRY) PIOS_COM_ChangeBaud(PIOS_COM_TELEMETRY, 57600);
|
||||
break;
|
||||
case OPLINKSETTINGS_COMSPEED_115200:
|
||||
if (is_coordinator && PIOS_COM_RADIO) PIOS_COM_ChangeBaud(PIOS_COM_RADIO, 115200);
|
||||
if (PIOS_COM_TELEMETRY) PIOS_COM_ChangeBaud(PIOS_COM_TELEMETRY, 115200);
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
@ -35,10 +35,6 @@
|
||||
#include "flighttelemetrystats.h"
|
||||
#include "gcstelemetrystats.h"
|
||||
#include "hwsettings.h"
|
||||
#if defined(PIOS_PACKET_HANDLER)
|
||||
#include "pipxstatus.h"
|
||||
#include "packet_handler.h"
|
||||
#endif
|
||||
|
||||
// Private constants
|
||||
#define MAX_QUEUE_SIZE TELEM_QUEUE_SIZE
|
||||
@ -84,9 +80,6 @@ static void updateTelemetryStats();
|
||||
static void gcsTelemetryStatsUpdated();
|
||||
static void updateSettings();
|
||||
static uint32_t getComPort();
|
||||
#ifdef PIOS_PACKET_HANDLER
|
||||
static void receivePacketData(uint8_t *buf, uint8_t len, int8_t rssi, int8_t afc);
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Initialise the telemetry module
|
||||
@ -100,13 +93,6 @@ int32_t TelemetryStart(void)
|
||||
|
||||
// Listen to objects of interest
|
||||
GCSTelemetryStatsConnectQueue(priorityQueue);
|
||||
|
||||
// Register to receive data from the radio packet handler.
|
||||
// This must be after the radio module is initialized.
|
||||
#ifdef PIOS_PACKET_HANDLER
|
||||
if (PIOS_PACKET_HANDLER)
|
||||
PHRegisterDataHandler(PIOS_PACKET_HANDLER, receivePacketData);
|
||||
#endif
|
||||
|
||||
// Start telemetry tasks
|
||||
xTaskCreate(telemetryTxTask, (signed char *)"TelTx", STACK_SIZE_BYTES/4, NULL, TASK_PRIORITY_TX, &telemetryTxTaskHandle);
|
||||
@ -281,11 +267,6 @@ static void processObjEvent(UAVObjEvent * ev)
|
||||
retries = 0;
|
||||
success = -1;
|
||||
if (ev->event == EV_UPDATED || ev->event == EV_UPDATED_MANUAL || ((ev->event == EV_UPDATED_PERIODIC) && (updateMode != UPDATEMODE_THROTTLED))) {
|
||||
#ifdef PIOS_PACKET_HANDLER
|
||||
// Don't send PipXStatus objects over the radio link.
|
||||
if (PIOS_PACKET_HANDLER && (ev->obj == PipXStatusHandle()) && (getComPort() == 0))
|
||||
return;
|
||||
#endif
|
||||
// Send update to GCS (with retries)
|
||||
while (retries < MAX_RETRIES && success == -1) {
|
||||
success = UAVTalkSendObject(uavTalkCon, ev->obj, ev->instId, UAVObjGetTelemetryAcked(&metadata), REQ_TIMEOUT_MS); // call blocks until ack is received or timeout
|
||||
@ -394,14 +375,9 @@ static int32_t transmitData(uint8_t * data, int32_t length)
|
||||
{
|
||||
uint32_t outputPort = getComPort();
|
||||
|
||||
if (outputPort) {
|
||||
if (outputPort)
|
||||
return PIOS_COM_SendBuffer(outputPort, data, length);
|
||||
}
|
||||
#ifdef PIOS_PACKET_HANDLER
|
||||
if (PIOS_PACKET_HANDLER)
|
||||
if (PHTransmitData(PIOS_PACKET_HANDLER, data, length))
|
||||
return length;
|
||||
#endif
|
||||
|
||||
return -1;
|
||||
}
|
||||
|
||||
@ -572,30 +548,20 @@ static void updateSettings()
|
||||
}
|
||||
|
||||
/**
|
||||
* Determine input/output com port (USB takes priority over telemetry port)
|
||||
* Determine input/output com port as highest priority available
|
||||
*/
|
||||
static uint32_t getComPort() {
|
||||
#if defined(PIOS_INCLUDE_USB)
|
||||
if (PIOS_USB_CheckAvailable(0) && PIOS_COM_TELEM_USB)
|
||||
if ( PIOS_COM_Available(PIOS_COM_TELEM_USB) )
|
||||
return PIOS_COM_TELEM_USB;
|
||||
else
|
||||
#endif /* PIOS_INCLUDE_USB */
|
||||
return telemetryPort;
|
||||
if ( PIOS_COM_Available(telemetryPort) )
|
||||
return telemetryPort;
|
||||
else
|
||||
return 0;
|
||||
}
|
||||
|
||||
#ifdef PIOS_PACKET_HANDLER
|
||||
/**
|
||||
* Receive a packet
|
||||
* \param[in] buf The received data buffer
|
||||
* \param[in] length Length of buffer
|
||||
*/
|
||||
static void receivePacketData(uint8_t *buf, uint8_t len, int8_t rssi, int8_t afc)
|
||||
{
|
||||
for (uint8_t i = 0; i < len; ++i)
|
||||
UAVTalkProcessInputStream(uavTalkCon, buf[i]);
|
||||
}
|
||||
#endif
|
||||
|
||||
/**
|
||||
* @}
|
||||
* @}
|
||||
|
@ -41,6 +41,7 @@ struct pios_com_driver {
|
||||
void (*rx_start)(uint32_t id, uint16_t rx_bytes_avail);
|
||||
void (*bind_rx_cb)(uint32_t id, pios_com_callback rx_in_cb, uint32_t context);
|
||||
void (*bind_tx_cb)(uint32_t id, pios_com_callback tx_out_cb, uint32_t context);
|
||||
bool (*available)(uint32_t id);
|
||||
};
|
||||
|
||||
/* Public Functions */
|
||||
@ -55,7 +56,7 @@ extern int32_t PIOS_COM_SendString(uint32_t com_id, const char *str);
|
||||
extern int32_t PIOS_COM_SendFormattedStringNonBlocking(uint32_t com_id, const char *format, ...);
|
||||
extern int32_t PIOS_COM_SendFormattedString(uint32_t com_id, const char *format, ...);
|
||||
extern uint16_t PIOS_COM_ReceiveBuffer(uint32_t com_id, uint8_t * buf, uint16_t buf_len, uint32_t timeout_ms);
|
||||
extern int32_t PIOS_COM_ReceiveBufferUsed(uint32_t com_id);
|
||||
extern bool PIOS_COM_Available(uint32_t com_id);
|
||||
|
||||
#endif /* PIOS_COM_H */
|
||||
|
||||
|
@ -497,21 +497,24 @@ uint16_t PIOS_COM_ReceiveBuffer(uint32_t com_id, uint8_t * buf, uint16_t buf_len
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the number of bytes waiting in the buffer
|
||||
* \param[in] port COM port
|
||||
* \return Number of bytes used in buffer
|
||||
*/
|
||||
int32_t PIOS_COM_ReceiveBufferUsed(uint32_t com_id)
|
||||
* Query if a com port is available for use. That can be
|
||||
* used to check a link is established even if the device
|
||||
* is valid.
|
||||
*/
|
||||
bool PIOS_COM_Available(uint32_t com_id)
|
||||
{
|
||||
struct pios_com_dev * com_dev = PIOS_COM_find_dev(com_id);
|
||||
|
||||
if (!PIOS_COM_validate(com_dev)) {
|
||||
/* Undefined COM port for this board (see pios_board.c) */
|
||||
PIOS_Assert(0);
|
||||
return false;
|
||||
}
|
||||
|
||||
PIOS_Assert(com_dev->has_rx);
|
||||
return (fifoBuf_getUsed(&com_dev->rx));
|
||||
// If a driver does not provide a query method assume always
|
||||
// available if valid
|
||||
if (com_dev->driver->available == NULL)
|
||||
return true;
|
||||
|
||||
return (com_dev->driver->available)(com_dev->lower_id);
|
||||
}
|
||||
|
||||
#endif
|
||||
|
@ -41,6 +41,7 @@ struct pios_com_driver {
|
||||
void (*rx_start)(uint32_t id, uint16_t rx_bytes_avail);
|
||||
void (*bind_rx_cb)(uint32_t id, pios_com_callback rx_in_cb, uint32_t context);
|
||||
void (*bind_tx_cb)(uint32_t id, pios_com_callback tx_out_cb, uint32_t context);
|
||||
bool (*available)(uint32_t id);
|
||||
};
|
||||
|
||||
/* Public Functions */
|
||||
@ -55,7 +56,7 @@ extern int32_t PIOS_COM_SendString(uint32_t com_id, const char *str);
|
||||
extern int32_t PIOS_COM_SendFormattedStringNonBlocking(uint32_t com_id, const char *format, ...);
|
||||
extern int32_t PIOS_COM_SendFormattedString(uint32_t com_id, const char *format, ...);
|
||||
extern uint16_t PIOS_COM_ReceiveBuffer(uint32_t com_id, uint8_t * buf, uint16_t buf_len, uint32_t timeout_ms);
|
||||
extern int32_t PIOS_COM_ReceiveBufferUsed(uint32_t com_id);
|
||||
extern bool PIOS_COM_Available(uint32_t com_id);
|
||||
|
||||
#endif /* PIOS_COM_H */
|
||||
|
||||
|
@ -497,21 +497,24 @@ uint16_t PIOS_COM_ReceiveBuffer(uint32_t com_id, uint8_t * buf, uint16_t buf_len
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the number of bytes waiting in the buffer
|
||||
* \param[in] port COM port
|
||||
* \return Number of bytes used in buffer
|
||||
*/
|
||||
int32_t PIOS_COM_ReceiveBufferUsed(uint32_t com_id)
|
||||
* Query if a com port is available for use. That can be
|
||||
* used to check a link is established even if the device
|
||||
* is valid.
|
||||
*/
|
||||
bool PIOS_COM_Available(uint32_t com_id)
|
||||
{
|
||||
struct pios_com_dev * com_dev = PIOS_COM_find_dev(com_id);
|
||||
|
||||
if (!PIOS_COM_validate(com_dev)) {
|
||||
/* Undefined COM port for this board (see pios_board.c) */
|
||||
PIOS_Assert(0);
|
||||
return false;
|
||||
}
|
||||
|
||||
PIOS_Assert(com_dev->has_rx);
|
||||
return (fifoBuf_getUsed(&com_dev->rx));
|
||||
// If a driver does not provide a query method assume always
|
||||
// available if valid
|
||||
if (com_dev->driver->available == NULL)
|
||||
return true;
|
||||
|
||||
return (com_dev->driver->available)(com_dev->lower_id);
|
||||
}
|
||||
|
||||
#endif
|
||||
|
@ -71,12 +71,10 @@ TIM4 | RC In 1 | Servo 3 | Servo 2 | Servo 1
|
||||
//------------------------
|
||||
#define PIOS_WATCHDOG_TIMEOUT 500
|
||||
#define PIOS_WDG_REGISTER BKP_DR4
|
||||
#define PIOS_WDG_COMGCS 0x0001
|
||||
#define PIOS_WDG_COMUAVTALK 0x0002
|
||||
#define PIOS_WDG_RADIORECEIVE 0x0004
|
||||
#define PIOS_WDG_SENDDATA 0x0008
|
||||
#define PIOS_WDG_TRANSCOMM 0x0008
|
||||
#define PIOS_WDG_PPMINPUT 0x0010
|
||||
#define PIOS_WDG_TELEMETRY 0x0001
|
||||
#define PIOS_WDG_RADIORX 0x0002
|
||||
#define PIOS_WDG_RADIOTX 0x0004
|
||||
#define PIOS_WDG_RFM22B 0x0008
|
||||
|
||||
//------------------------
|
||||
// TELEMETRY
|
||||
@ -90,6 +88,12 @@ TIM4 | RC In 1 | Servo 3 | Servo 2 | Servo 1
|
||||
#define PIOS_LED_LINK 1
|
||||
#define PIOS_LED_RX 2
|
||||
#define PIOS_LED_TX 3
|
||||
#ifdef PIOS_RFM22B_DEBUG_ON_TELEM
|
||||
#define PIOS_LED_D1 4
|
||||
#define PIOS_LED_D2 5
|
||||
#define PIOS_LED_D3 6
|
||||
#define PIOS_LED_D4 7
|
||||
#endif
|
||||
|
||||
#define PIOS_LED_HEARTBEAT PIOS_LED_USB
|
||||
#define PIOS_LED_ALARM PIOS_LED_TX
|
||||
@ -110,6 +114,24 @@ TIM4 | RC In 1 | Servo 3 | Servo 2 | Servo 1
|
||||
#define TX_LED_OFF PIOS_LED_Off(PIOS_LED_TX)
|
||||
#define TX_LED_TOGGLE PIOS_LED_Toggle(PIOS_LED_TX)
|
||||
|
||||
#ifdef PIOS_RFM22B_DEBUG_ON_TELEM
|
||||
#define D1_LED_ON PIOS_LED_On(PIOS_LED_D1)
|
||||
#define D1_LED_OFF PIOS_LED_Off(PIOS_LED_D1)
|
||||
#define D1_LED_TOGGLE PIOS_LED_Toggle(PIOS_LED_D1)
|
||||
|
||||
#define D2_LED_ON PIOS_LED_On(PIOS_LED_D2)
|
||||
#define D2_LED_OFF PIOS_LED_Off(PIOS_LED_D2)
|
||||
#define D2_LED_TOGGLE PIOS_LED_Toggle(PIOS_LED_D2)
|
||||
|
||||
#define D3_LED_ON PIOS_LED_On(PIOS_LED_D3)
|
||||
#define D3_LED_OFF PIOS_LED_Off(PIOS_LED_D3)
|
||||
#define D3_LED_TOGGLE PIOS_LED_Toggle(PIOS_LED_D3)
|
||||
|
||||
#define D4_LED_ON PIOS_LED_On(PIOS_LED_D4)
|
||||
#define D4_LED_OFF PIOS_LED_Off(PIOS_LED_D4)
|
||||
#define D4_LED_TOGGLE PIOS_LED_Toggle(PIOS_LED_D4)
|
||||
#endif
|
||||
|
||||
//-------------------------
|
||||
// System Settings
|
||||
//-------------------------
|
||||
@ -151,29 +173,24 @@ extern uint32_t pios_i2c_flexi_adapter_id;
|
||||
#define PIOS_COM_MAX_DEVS 5
|
||||
|
||||
extern uint32_t pios_com_telem_usb_id;
|
||||
extern uint32_t pios_com_telem_vcp_id;
|
||||
extern uint32_t pios_com_telem_uart_telem_id;
|
||||
extern uint32_t pios_com_telem_uart_flexi_id;
|
||||
extern uint32_t pios_com_telemetry_id;
|
||||
extern uint32_t pios_com_flexi_id;
|
||||
extern uint32_t pios_com_vcp_id;
|
||||
extern uint32_t pios_com_uavtalk_com_id;
|
||||
extern uint32_t pios_com_gcs_com_id;
|
||||
extern uint32_t pios_com_trans_com_id;
|
||||
extern uint32_t pios_com_debug_id;
|
||||
extern uint32_t pios_com_rfm22b_id;
|
||||
extern uint32_t pios_com_radio_id;
|
||||
extern uint32_t pios_ppm_rcvr_id;
|
||||
#define PIOS_COM_USB_HID (pios_com_telem_usb_id)
|
||||
#define PIOS_COM_TELEM_USB (pios_com_telem_usb_id)
|
||||
#define PIOS_COM_TELEM_VCP (pios_com_telem_vcp_id)
|
||||
#define PIOS_COM_TELEM_UART_FLEXI (pios_com_telem_uart_flexi_id)
|
||||
#define PIOS_COM_TELEM_UART_TELEM (pios_com_telem_uart_telem_id)
|
||||
#define PIOS_COM_TELEMETRY (pios_com_telemetry_id)
|
||||
#define PIOS_COM_FLEXI (pios_com_flexi_id)
|
||||
#define PIOS_COM_VCP (pios_com_vcp_id)
|
||||
#define PIOS_COM_UAVTALK (pios_com_uavtalk_com_id)
|
||||
#define PIOS_COM_GCS (pios_com_gcs_com_id)
|
||||
#define PIOS_COM_TRANS_COM (pios_com_trans_com_id)
|
||||
#define PIOS_COM_DEBUG (pios_com_debug_id)
|
||||
#define PIOS_COM_RADIO (pios_com_rfm22b_id)
|
||||
#define PIOS_COM_TELEM_USB PIOS_COM_USB_HID
|
||||
#define PIOS_COM_RFM22B (pios_com_rfm22b_id)
|
||||
#define PIOS_COM_RADIO (pios_com_radio_id)
|
||||
#define PIOS_PPM_RECEIVER (pios_ppm_rcvr_id)
|
||||
|
||||
#define DEBUG_LEVEL 2
|
||||
#if DEBUG_LEVEL > 0
|
||||
#if DEBUG_LEVEL > 1000
|
||||
#define DEBUG_PRINTF(level, ...) {if(level <= DEBUG_LEVEL && PIOS_COM_DEBUG > 0) { PIOS_COM_SendFormattedStringNonBlocking(PIOS_COM_DEBUG, __VA_ARGS__); }}
|
||||
#else
|
||||
#define DEBUG_PRINTF(...)
|
||||
@ -230,8 +247,7 @@ extern uint32_t pios_ppm_rcvr_id;
|
||||
// Receiver PPM input
|
||||
//-------------------------
|
||||
#define PIOS_PPM_MAX_DEVS 1
|
||||
#define PIOS_PPM_NUM_INPUTS 12
|
||||
#define PIOS_PPM_PACKET_UPDATE_PERIOD_MS 25
|
||||
#define PIOS_PPM_NUM_INPUTS 8
|
||||
|
||||
//-------------------------
|
||||
// Servo outputs
|
||||
@ -268,13 +284,8 @@ extern uint32_t pios_ppm_rcvr_id;
|
||||
//-------------------------
|
||||
|
||||
#if defined(PIOS_INCLUDE_RFM22B)
|
||||
#define PIOS_COM_RFM22B_RF_RX_BUF_LEN 256
|
||||
#define PIOS_COM_RFM22B_RF_TX_BUF_LEN 256
|
||||
extern uint32_t pios_com_rfm22b_id;
|
||||
#define PIOS_COM_RADIO (pios_com_rfm22b_id)
|
||||
extern uint32_t pios_spi_rfm22b_id;
|
||||
#define PIOS_RFM22_SPI_PORT (pios_spi_rfm22b_id)
|
||||
#define RFM22_EXT_INT_USE
|
||||
extern uint32_t pios_rfm22b_id;
|
||||
#endif /* PIOS_INCLUDE_RFM22B */
|
||||
|
||||
|
@ -33,7 +33,7 @@
|
||||
|
||||
#if defined(PIOS_INCLUDE_DEBUG_CONSOLE)
|
||||
#define DEBUG_LEVEL 0
|
||||
#define DEBUG_PRINTF(level, ...) {if(level <= DEBUG_LEVEL && pios_com_aux_id > 0) { PIOS_COM_SendFormattedStringNonBlocking(pios_com_aux_id, __VA_ARGS__); }}
|
||||
#define DEBUG_PRINTF(level, ...) {if(level <= DEBUG_LEVEL && pios_com_debug_id > 0) { PIOS_COM_SendFormattedStringNonBlocking(pios_com_debug_id, __VA_ARGS__); }}
|
||||
#else
|
||||
#define DEBUG_PRINTF(level, ...)
|
||||
#endif /* PIOS_INCLUDE_DEBUG_CONSOLE */
|
||||
@ -143,10 +143,7 @@ extern uint32_t pios_com_debug_id;
|
||||
#endif /* PIOS_INCLUDE_DEBUG_CONSOLE */
|
||||
|
||||
#if defined(PIOS_INCLUDE_RFM22B)
|
||||
#define PIOS_COM_RFM22B_RF_RX_BUF_LEN 512
|
||||
#define PIOS_COM_RFM22B_RF_TX_BUF_LEN 512
|
||||
extern uint32_t pios_com_rfm22b_id;
|
||||
#define PIOS_COM_RADIO (pios_com_rfm22b_id)
|
||||
extern uint32_t pios_rfm22b_id;
|
||||
extern uint32_t pios_spi_telem_flash_id;
|
||||
#define PIOS_RFM22_SPI_PORT (pios_spi_telem_flash_id)
|
||||
#endif /* PIOS_INCLUDE_RFM22B */
|
||||
@ -217,6 +214,7 @@ extern uint32_t pios_packet_handler;
|
||||
#define PIOS_RCVR_MAX_DEVS 3
|
||||
#define PIOS_RCVR_MAX_CHANNELS 12
|
||||
#define PIOS_GCSRCVR_TIMEOUT_MS 100
|
||||
#define PIOS_RFM22B_RCVR_TIMEOUT_MS 100
|
||||
|
||||
//-------------------------
|
||||
// Receiver PPM input
|
||||
|
@ -503,6 +503,27 @@ uint16_t PIOS_COM_ReceiveBuffer(uint32_t com_id, uint8_t * buf, uint16_t buf_len
|
||||
return (bytes_from_fifo);
|
||||
}
|
||||
|
||||
/**
|
||||
* Query if a com port is available for use. That can be
|
||||
* used to check a link is established even if the device
|
||||
* is valid.
|
||||
*/
|
||||
bool PIOS_COM_Available(uint32_t com_id)
|
||||
{
|
||||
struct pios_com_dev * com_dev = (struct pios_com_dev *)com_id;
|
||||
|
||||
if (!PIOS_COM_validate(com_dev)) {
|
||||
return false;
|
||||
}
|
||||
|
||||
// If a driver does not provide a query method assume always
|
||||
// available if valid
|
||||
if (com_dev->driver->available == NULL)
|
||||
return true;
|
||||
|
||||
return (com_dev->driver->available)(com_dev->lower_id);
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
/**
|
||||
|
@ -59,17 +59,33 @@
|
||||
/* Local Defines */
|
||||
#define STACK_SIZE_BYTES 200
|
||||
#define TASK_PRIORITY (tskIDLE_PRIORITY + 2)
|
||||
#define ISR_TIMEOUT 5 // ms
|
||||
#define ISR_TIMEOUT 2 // ms
|
||||
#define EVENT_QUEUE_SIZE 5
|
||||
#define PACKET_QUEUE_SIZE 3
|
||||
#define RFM22B_DEFAULT_RX_DATARATE RFM22_datarate_64000
|
||||
#define RFM22B_DEFAULT_RX_DATARATE RFM22_datarate_9600
|
||||
#define RFM22B_DEFAULT_FREQUENCY 434000000
|
||||
#define RFM22B_DEFAULT_MIN_FREQUENCY (RFM22B_DEFAULT_FREQUENCY - 2000000)
|
||||
#define RFM22B_DEFAULT_MAX_FREQUENCY (RFM22B_DEFAULT_FREQUENCY + 2000000)
|
||||
#define RFM22B_DEFAULT_TX_POWER RFM22_tx_pwr_txpow_7
|
||||
#define RFM22B_LINK_QUALITY_THRESHOLD 20
|
||||
|
||||
// The maximum amount of time since the last message received to consider the connection broken.
|
||||
#define DISCONNECT_TIMEOUT_MS 1000 // ms
|
||||
|
||||
// The maximum amount of time without activity before initiating a reset.
|
||||
#define PIOS_RFM22B_SUPERVISOR_TIMEOUT 100 // ms
|
||||
|
||||
// The time between updates over the radio link.
|
||||
// The time between connection attempts when not connected
|
||||
#define CONNECT_ATTEMPT_PERIOD_MS 250 // 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 40
|
||||
|
||||
// this is too adjust the RF module so that it is on frequency
|
||||
#define OSC_LOAD_CAP 0x7F // cap = 12.5pf .. default
|
||||
#define OSC_LOAD_CAP_1 0x7D // board 1
|
||||
@ -119,156 +135,6 @@
|
||||
// AFC enabled
|
||||
|
||||
/* Local type definitions */
|
||||
enum pios_rfm22b_dev_magic {
|
||||
PIOS_RFM22B_DEV_MAGIC = 0x68e971b6,
|
||||
};
|
||||
|
||||
enum pios_rfm22b_state {
|
||||
RFM22B_STATE_UNINITIALIZED,
|
||||
RFM22B_STATE_INITIALIZING,
|
||||
RFM22B_STATE_RX_MODE,
|
||||
RFM22B_STATE_WAIT_PREAMBLE,
|
||||
RFM22B_STATE_WAIT_SYNC,
|
||||
RFM22B_STATE_RX_DATA,
|
||||
RFM22B_STATE_TX_START,
|
||||
RFM22B_STATE_TX_DATA,
|
||||
RFM22B_STATE_TIMEOUT,
|
||||
RFM22B_STATE_ERROR,
|
||||
RFM22B_STATE_FATAL_ERROR,
|
||||
|
||||
RFM22B_STATE_NUM_STATES // Must be last
|
||||
};
|
||||
|
||||
enum pios_rfm22b_event {
|
||||
RFM22B_EVENT_INITIALIZE,
|
||||
RFM22B_EVENT_INITIALIZED,
|
||||
RFM22B_EVENT_INT_RECEIVED,
|
||||
RFM22B_EVENT_RX_MODE,
|
||||
RFM22B_EVENT_PREAMBLE_DETECTED,
|
||||
RFM22B_EVENT_SYNC_DETECTED,
|
||||
RFM22B_EVENT_RX_COMPLETE,
|
||||
RFM22B_EVENT_SEND_PACKET,
|
||||
RFM22B_EVENT_TX_START,
|
||||
RFM22B_EVENT_TX_STARTED,
|
||||
RFM22B_EVENT_TX_COMPLETE,
|
||||
RFM22B_EVENT_TIMEOUT,
|
||||
RFM22B_EVENT_ERROR,
|
||||
RFM22B_EVENT_FATAL_ERROR,
|
||||
|
||||
RFM22B_EVENT_NUM_EVENTS // Must be last
|
||||
};
|
||||
|
||||
struct pios_rfm22b_dev {
|
||||
enum pios_rfm22b_dev_magic magic;
|
||||
struct pios_rfm22b_cfg cfg;
|
||||
|
||||
uint32_t spi_id;
|
||||
uint32_t slave_num;
|
||||
|
||||
// The device ID
|
||||
uint32_t deviceID;
|
||||
|
||||
// The destination ID
|
||||
uint32_t destination_id;
|
||||
|
||||
// The task handle
|
||||
xTaskHandle taskHandle;
|
||||
|
||||
// ISR pending
|
||||
xSemaphoreHandle isrPending;
|
||||
|
||||
// Receive packet complete
|
||||
xSemaphoreHandle rxsem;
|
||||
|
||||
// The COM callback functions.
|
||||
pios_com_callback rx_in_cb;
|
||||
uint32_t rx_in_context;
|
||||
pios_com_callback tx_out_cb;
|
||||
uint32_t tx_out_context;
|
||||
|
||||
// the transmit power to use for data transmissions
|
||||
uint8_t tx_power;
|
||||
|
||||
// The RF datarate lookup index.
|
||||
uint8_t datarate;
|
||||
|
||||
// The state machine state and the current event
|
||||
enum pios_rfm22b_state state;
|
||||
// The event queue handle
|
||||
xQueueHandle eventQueue;
|
||||
|
||||
// device status register
|
||||
uint8_t device_status;
|
||||
// interrupt status register 1
|
||||
uint8_t int_status1;
|
||||
// interrupt status register 2
|
||||
uint8_t int_status2;
|
||||
// ezmac status register
|
||||
uint8_t ezmac_status;
|
||||
|
||||
// The packet transmission counts
|
||||
uint32_t tx_packet_count;
|
||||
uint32_t rx_packet_count;
|
||||
|
||||
// The dropped packet counters
|
||||
uint8_t slow_block;
|
||||
uint8_t fast_block;
|
||||
uint8_t slow_good_packets;
|
||||
uint8_t fast_good_packets;
|
||||
uint8_t slow_corrected_packets;
|
||||
uint8_t fast_corrected_packets;
|
||||
uint8_t slow_error_packets;
|
||||
uint8_t fast_error_packets;
|
||||
uint8_t slow_link_quality;
|
||||
uint8_t fast_link_quality;
|
||||
|
||||
// Stats
|
||||
uint16_t resets;
|
||||
uint16_t timeouts;
|
||||
uint16_t errors;
|
||||
// the current RSSI (register value)
|
||||
uint8_t rssi;
|
||||
// RSSI in dBm
|
||||
int8_t rssi_dBm;
|
||||
|
||||
// The packet queue handle
|
||||
xQueueHandle packetQueue;
|
||||
|
||||
// The current tx packet
|
||||
PHPacketHandle tx_packet;
|
||||
// the tx data read index
|
||||
uint16_t tx_data_rd;
|
||||
// the tx data write index
|
||||
uint16_t tx_data_wr;
|
||||
|
||||
// The current rx packet
|
||||
PHPacketHandle rx_packet;
|
||||
// The previous rx packet
|
||||
PHPacketHandle rx_packet_prev;
|
||||
// The next rx packet
|
||||
PHPacketHandle rx_packet_next;
|
||||
// the receive buffer write index
|
||||
uint16_t rx_buffer_wr;
|
||||
// the receive buffer write index
|
||||
uint16_t rx_packet_len;
|
||||
|
||||
// The frequency hopping step size
|
||||
float frequency_step_size;
|
||||
// current frequency hop channel
|
||||
uint8_t frequency_hop_channel;
|
||||
// the frequency hop step size
|
||||
uint8_t frequency_hop_step_size_reg;
|
||||
// afc correction reading (in Hz)
|
||||
int32_t afc_correction_Hz;
|
||||
int8_t rx_packet_start_afc_Hz;
|
||||
|
||||
// The status packet
|
||||
PHStatusPacket status_packet;
|
||||
|
||||
// The maximum time (ms) that it should take to transmit / receive a packet.
|
||||
uint32_t max_packet_time;
|
||||
portTickType packet_start_ticks;
|
||||
};
|
||||
|
||||
struct pios_rfm22b_transition {
|
||||
enum pios_rfm22b_event (*entry_fn) (struct pios_rfm22b_dev *rfm22b_dev);
|
||||
@ -302,48 +168,53 @@ static const uint8_t OUT_FF[64] = {0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,
|
||||
|
||||
/* Local function forwared declarations */
|
||||
static void PIOS_RFM22B_Task(void *parameters);
|
||||
static void PIOS_RFM22B_InjectEvent(struct pios_rfm22b_dev *rfm22b_dev, enum pios_rfm22b_event event, bool inISR);
|
||||
static bool rfm22_readStatus(struct pios_rfm22b_dev *rfm22b_dev);
|
||||
static void rfm22_setDatarate(struct pios_rfm22b_dev * rfm22b_dev, enum rfm22b_datarate datarate, bool data_whitening);
|
||||
static enum pios_rfm22b_event rfm22_init(struct pios_rfm22b_dev *rfm22b_dev);
|
||||
static enum pios_rfm22b_event rfm22_setRxMode(struct pios_rfm22b_dev *rfm22b_dev);
|
||||
static enum pios_rfm22b_event rfm22_detectPreamble(struct pios_rfm22b_dev *rfm22b_dev);
|
||||
static enum pios_rfm22b_event rfm22_detectSync(struct pios_rfm22b_dev *rfm22b_dev);
|
||||
static enum pios_rfm22b_event rfm22_rxData(struct pios_rfm22b_dev *rfm22b_dev);
|
||||
static enum pios_rfm22b_event rfm22_init(struct pios_rfm22b_dev *rfm22b_dev);
|
||||
static enum pios_rfm22b_event rfm22_rxFailure(struct pios_rfm22b_dev *rfm22b_dev);
|
||||
static enum pios_rfm22b_event rfm22_receiveStatus(struct pios_rfm22b_dev *rfm22b_dev);
|
||||
static enum pios_rfm22b_event rfm22_receiveAck(struct pios_rfm22b_dev *rfm22b_dev);
|
||||
static enum pios_rfm22b_event rfm22_receiveNack(struct pios_rfm22b_dev *rfm22b_dev);
|
||||
static enum pios_rfm22b_event rfm22_sendAck(struct pios_rfm22b_dev *rfm22b_dev);
|
||||
static enum pios_rfm22b_event rfm22_sendNack(struct pios_rfm22b_dev *rfm22b_dev);
|
||||
static enum pios_rfm22b_event rfm22_requestConnection(struct pios_rfm22b_dev *rfm22b_dev);
|
||||
static enum pios_rfm22b_event rfm22_initConnection(struct pios_rfm22b_dev *rfm22b_dev);
|
||||
static enum pios_rfm22b_event rfm22_acceptConnection(struct pios_rfm22b_dev *rfm22b_dev);
|
||||
static enum pios_rfm22b_event rfm22_txStart(struct pios_rfm22b_dev *rfm22b_dev);
|
||||
static enum pios_rfm22b_event rfm22_txData(struct pios_rfm22b_dev *rfm22b_dev);
|
||||
static enum pios_rfm22b_event rfm22_txFailure(struct pios_rfm22b_dev *rfm22b_dev);
|
||||
static enum pios_rfm22b_event rfm22_process_state_transition(struct pios_rfm22b_dev *rfm22b_dev, enum pios_rfm22b_event event);
|
||||
static void rfm22_process_event(struct pios_rfm22b_dev *rfm22b_dev, enum pios_rfm22b_event event);
|
||||
static enum pios_rfm22b_event rfm22_timeout(struct pios_rfm22b_dev *rfm22b_dev);
|
||||
static enum pios_rfm22b_event rfm22_error(struct pios_rfm22b_dev *rfm22b_dev);
|
||||
static enum pios_rfm22b_event rfm22_fatal_error(struct pios_rfm22b_dev *rfm22b_dev);
|
||||
static bool rfm22_sendStatus(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 bool rfm22_receivePacket(struct pios_rfm22b_dev *rfm22b_dev, PHPacketHandle p, uint16_t rx_len);
|
||||
static void rfm22_setNominalCarrierFrequency(struct pios_rfm22b_dev *rfm22b_dev, uint32_t frequency_hz);
|
||||
static void rfm22_calculateLinkQuality(struct pios_rfm22b_dev *rfm22b_dev);
|
||||
static bool rfm22_ready_to_send(struct pios_rfm22b_dev *rfm22b_dev);
|
||||
static void rfm22_setConnectionParameters(struct pios_rfm22b_dev *rfm22b_dev);
|
||||
static void rfm22_clearLEDs();
|
||||
|
||||
// SPI read/write functions
|
||||
static void rfm22_assertCs();
|
||||
static void rfm22_deassertCs();
|
||||
static void rfm22_claimBus();
|
||||
static void rfm22_releaseBus();
|
||||
static void rfm22_write(uint8_t addr, uint8_t data);
|
||||
static uint8_t rfm22_read(uint8_t addr);
|
||||
static uint8_t rfm22_read_noclaim(uint8_t addr);
|
||||
|
||||
/* Provide a COM driver */
|
||||
static void PIOS_RFM22B_ChangeBaud(uint32_t rfm22b_id, uint32_t baud);
|
||||
static void PIOS_RFM22B_RegisterRxCallback(uint32_t rfm22b_id, pios_com_callback rx_in_cb, uint32_t context);
|
||||
static void PIOS_RFM22B_RegisterTxCallback(uint32_t rfm22b_id, pios_com_callback tx_out_cb, uint32_t context);
|
||||
static void PIOS_RFM22B_TxStart(uint32_t rfm22b_id, uint16_t tx_bytes_avail);
|
||||
static void PIOS_RFM22B_RxStart(uint32_t rfm22b_id, uint16_t rx_bytes_avail);
|
||||
|
||||
/* Local variables */
|
||||
const struct pios_com_driver pios_rfm22b_com_driver = {
|
||||
.set_baud = PIOS_RFM22B_ChangeBaud,
|
||||
.tx_start = PIOS_RFM22B_TxStart,
|
||||
.rx_start = PIOS_RFM22B_RxStart,
|
||||
.bind_tx_cb = PIOS_RFM22B_RegisterTxCallback,
|
||||
.bind_rx_cb = PIOS_RFM22B_RegisterRxCallback,
|
||||
};
|
||||
static void rfm22_assertCs(struct pios_rfm22b_dev *rfm22b_dev);
|
||||
static void rfm22_deassertCs(struct pios_rfm22b_dev *rfm22b_dev);
|
||||
static void rfm22_claimBus(struct pios_rfm22b_dev *rfm22b_dev);
|
||||
static void rfm22_releaseBus(struct pios_rfm22b_dev *rfm22b_dev);
|
||||
static void rfm22_write(struct pios_rfm22b_dev *rfm22b_dev, uint8_t addr, uint8_t data);
|
||||
static uint8_t rfm22_read(struct pios_rfm22b_dev *rfm22b_dev, uint8_t addr);
|
||||
static uint8_t rfm22_read_noclaim(struct pios_rfm22b_dev *rfm22b_dev, uint8_t addr);
|
||||
|
||||
/* Te state transition table */
|
||||
const static struct pios_rfm22b_transition rfm22b_transitions[RFM22B_STATE_NUM_STATES] = {
|
||||
|
||||
// Initialization thread
|
||||
[RFM22B_STATE_UNINITIALIZED] = {
|
||||
.entry_fn = 0,
|
||||
.next_state = {
|
||||
@ -354,31 +225,68 @@ const static struct pios_rfm22b_transition rfm22b_transitions[RFM22B_STATE_NUM_S
|
||||
[RFM22B_STATE_INITIALIZING] = {
|
||||
.entry_fn = rfm22_init,
|
||||
.next_state = {
|
||||
[RFM22B_EVENT_INITIALIZED] = RFM22B_STATE_TX_START,
|
||||
[RFM22B_EVENT_INITIALIZED] = RFM22B_STATE_INITIATING_CONNECTION,
|
||||
[RFM22B_EVENT_INITIALIZE] = RFM22B_STATE_INITIALIZING,
|
||||
[RFM22B_EVENT_ERROR] = RFM22B_STATE_ERROR,
|
||||
[RFM22B_EVENT_FATAL_ERROR] = RFM22B_STATE_FATAL_ERROR,
|
||||
},
|
||||
},
|
||||
[RFM22B_STATE_INITIATING_CONNECTION] = {
|
||||
.entry_fn = rfm22_initConnection,
|
||||
.next_state = {
|
||||
[RFM22B_EVENT_REQUEST_CONNECTION] = RFM22B_STATE_REQUESTING_CONNECTION,
|
||||
[RFM22B_EVENT_WAIT_FOR_CONNECTION] = RFM22B_STATE_RX_MODE,
|
||||
[RFM22B_EVENT_TIMEOUT] = RFM22B_STATE_TIMEOUT,
|
||||
[RFM22B_EVENT_ERROR] = RFM22B_STATE_ERROR,
|
||||
[RFM22B_EVENT_INITIALIZE] = RFM22B_STATE_INITIALIZING,
|
||||
[RFM22B_EVENT_FATAL_ERROR] = RFM22B_STATE_FATAL_ERROR,
|
||||
},
|
||||
},
|
||||
[RFM22B_STATE_REQUESTING_CONNECTION] = {
|
||||
.entry_fn = rfm22_requestConnection,
|
||||
.next_state = {
|
||||
[RFM22B_EVENT_TX_START] = RFM22B_STATE_TX_START,
|
||||
[RFM22B_EVENT_TIMEOUT] = RFM22B_STATE_TIMEOUT,
|
||||
[RFM22B_EVENT_ERROR] = RFM22B_STATE_ERROR,
|
||||
[RFM22B_EVENT_INITIALIZE] = RFM22B_STATE_INITIALIZING,
|
||||
[RFM22B_EVENT_FATAL_ERROR] = RFM22B_STATE_FATAL_ERROR,
|
||||
},
|
||||
},
|
||||
[RFM22B_STATE_ACCEPTING_CONNECTION] = {
|
||||
.entry_fn = rfm22_acceptConnection,
|
||||
.next_state = {
|
||||
[RFM22B_EVENT_CONNECTION_ACCEPTED] = RFM22B_STATE_SENDING_ACK,
|
||||
[RFM22B_EVENT_TIMEOUT] = RFM22B_STATE_TIMEOUT,
|
||||
[RFM22B_EVENT_ERROR] = RFM22B_STATE_ERROR,
|
||||
[RFM22B_EVENT_INITIALIZE] = RFM22B_STATE_INITIALIZING,
|
||||
[RFM22B_EVENT_FATAL_ERROR] = RFM22B_STATE_FATAL_ERROR,
|
||||
},
|
||||
},
|
||||
|
||||
[RFM22B_STATE_RX_MODE] = {
|
||||
.entry_fn = rfm22_setRxMode,
|
||||
.next_state = {
|
||||
[RFM22B_EVENT_INT_RECEIVED] = RFM22B_STATE_WAIT_PREAMBLE,
|
||||
[RFM22B_EVENT_SEND_PACKET] = RFM22B_STATE_TX_START,
|
||||
[RFM22B_EVENT_TX_START] = RFM22B_STATE_TX_START,
|
||||
[RFM22B_EVENT_ACK_TIMEOUT] = RFM22B_STATE_RECEIVING_NACK,
|
||||
[RFM22B_EVENT_FAILURE] = RFM22B_STATE_RX_FAILURE,
|
||||
[RFM22B_EVENT_TIMEOUT] = RFM22B_STATE_TIMEOUT,
|
||||
[RFM22B_EVENT_ERROR] = RFM22B_STATE_ERROR,
|
||||
[RFM22B_EVENT_INITIALIZE] = RFM22B_STATE_INITIALIZING,
|
||||
[RFM22B_EVENT_FATAL_ERROR] = RFM22B_STATE_FATAL_ERROR,
|
||||
},
|
||||
},
|
||||
[RFM22B_STATE_WAIT_PREAMBLE] = {
|
||||
.entry_fn = rfm22_detectPreamble,
|
||||
.next_state = {
|
||||
[RFM22B_EVENT_INT_RECEIVED] = RFM22B_STATE_WAIT_PREAMBLE,
|
||||
[RFM22B_EVENT_PREAMBLE_DETECTED] = RFM22B_STATE_WAIT_SYNC,
|
||||
[RFM22B_EVENT_SEND_PACKET] = RFM22B_STATE_TX_START,
|
||||
[RFM22B_EVENT_TX_START] = RFM22B_STATE_TX_START,
|
||||
[RFM22B_EVENT_ACK_TIMEOUT] = RFM22B_STATE_RECEIVING_NACK,
|
||||
[RFM22B_EVENT_INT_RECEIVED] = RFM22B_STATE_WAIT_PREAMBLE,
|
||||
[RFM22B_EVENT_FAILURE] = RFM22B_STATE_RX_FAILURE,
|
||||
[RFM22B_EVENT_TIMEOUT] = RFM22B_STATE_TIMEOUT,
|
||||
[RFM22B_EVENT_ERROR] = RFM22B_STATE_ERROR,
|
||||
[RFM22B_EVENT_INITIALIZE] = RFM22B_STATE_INITIALIZING,
|
||||
[RFM22B_EVENT_FATAL_ERROR] = RFM22B_STATE_FATAL_ERROR,
|
||||
},
|
||||
},
|
||||
@ -387,9 +295,10 @@ const static struct pios_rfm22b_transition rfm22b_transitions[RFM22B_STATE_NUM_S
|
||||
.next_state = {
|
||||
[RFM22B_EVENT_INT_RECEIVED] = RFM22B_STATE_WAIT_SYNC,
|
||||
[RFM22B_EVENT_SYNC_DETECTED] = RFM22B_STATE_RX_DATA,
|
||||
[RFM22B_EVENT_TX_START] = RFM22B_STATE_TX_START,
|
||||
[RFM22B_EVENT_FAILURE] = RFM22B_STATE_RX_FAILURE,
|
||||
[RFM22B_EVENT_TIMEOUT] = RFM22B_STATE_TIMEOUT,
|
||||
[RFM22B_EVENT_ERROR] = RFM22B_STATE_ERROR,
|
||||
[RFM22B_EVENT_INITIALIZE] = RFM22B_STATE_INITIALIZING,
|
||||
[RFM22B_EVENT_FATAL_ERROR] = RFM22B_STATE_FATAL_ERROR,
|
||||
},
|
||||
},
|
||||
@ -397,9 +306,57 @@ const static struct pios_rfm22b_transition rfm22b_transitions[RFM22B_STATE_NUM_S
|
||||
.entry_fn = rfm22_rxData,
|
||||
.next_state = {
|
||||
[RFM22B_EVENT_INT_RECEIVED] = RFM22B_STATE_RX_DATA,
|
||||
[RFM22B_EVENT_RX_COMPLETE] = RFM22B_STATE_TX_START,
|
||||
[RFM22B_EVENT_RX_COMPLETE] = RFM22B_STATE_SENDING_ACK,
|
||||
[RFM22B_EVENT_RX_ERROR] = RFM22B_STATE_SENDING_NACK,
|
||||
[RFM22B_EVENT_STATUS_RECEIVED] = RFM22B_STATE_RECEIVING_STATUS,
|
||||
[RFM22B_EVENT_CONNECTION_REQUESTED] = RFM22B_STATE_ACCEPTING_CONNECTION,
|
||||
[RFM22B_EVENT_PACKET_ACKED] = RFM22B_STATE_RECEIVING_ACK,
|
||||
[RFM22B_EVENT_PACKET_NACKED] = RFM22B_STATE_RECEIVING_NACK,
|
||||
[RFM22B_EVENT_FAILURE] = RFM22B_STATE_RX_FAILURE,
|
||||
[RFM22B_EVENT_TIMEOUT] = RFM22B_STATE_TIMEOUT,
|
||||
[RFM22B_EVENT_ERROR] = RFM22B_STATE_ERROR,
|
||||
[RFM22B_EVENT_INITIALIZE] = RFM22B_STATE_INITIALIZING,
|
||||
[RFM22B_EVENT_FATAL_ERROR] = RFM22B_STATE_FATAL_ERROR,
|
||||
},
|
||||
},
|
||||
[RFM22B_STATE_RX_FAILURE] = {
|
||||
.entry_fn = rfm22_rxFailure,
|
||||
.next_state = {
|
||||
[RFM22B_EVENT_RX_MODE] = RFM22B_STATE_RX_MODE,
|
||||
[RFM22B_EVENT_TIMEOUT] = RFM22B_STATE_TIMEOUT,
|
||||
[RFM22B_EVENT_ERROR] = RFM22B_STATE_ERROR,
|
||||
[RFM22B_EVENT_INITIALIZE] = RFM22B_STATE_INITIALIZING,
|
||||
[RFM22B_EVENT_FATAL_ERROR] = RFM22B_STATE_FATAL_ERROR,
|
||||
},
|
||||
},
|
||||
[RFM22B_STATE_RECEIVING_ACK] = {
|
||||
.entry_fn = rfm22_receiveAck,
|
||||
.next_state = {
|
||||
[RFM22B_EVENT_TX_START] = RFM22B_STATE_TX_START,
|
||||
[RFM22B_EVENT_RX_MODE] = RFM22B_STATE_RX_MODE,
|
||||
[RFM22B_EVENT_TIMEOUT] = RFM22B_STATE_TIMEOUT,
|
||||
[RFM22B_EVENT_ERROR] = RFM22B_STATE_ERROR,
|
||||
[RFM22B_EVENT_INITIALIZE] = RFM22B_STATE_INITIALIZING,
|
||||
[RFM22B_EVENT_FATAL_ERROR] = RFM22B_STATE_FATAL_ERROR,
|
||||
},
|
||||
},
|
||||
[RFM22B_STATE_RECEIVING_NACK] = {
|
||||
.entry_fn = rfm22_receiveNack,
|
||||
.next_state = {
|
||||
[RFM22B_EVENT_TX_START] = RFM22B_STATE_TX_START,
|
||||
[RFM22B_EVENT_TIMEOUT] = RFM22B_STATE_TIMEOUT,
|
||||
[RFM22B_EVENT_ERROR] = RFM22B_STATE_ERROR,
|
||||
[RFM22B_EVENT_INITIALIZE] = RFM22B_STATE_INITIALIZING,
|
||||
[RFM22B_EVENT_FATAL_ERROR] = RFM22B_STATE_FATAL_ERROR,
|
||||
},
|
||||
},
|
||||
[RFM22B_STATE_RECEIVING_STATUS] = {
|
||||
.entry_fn = rfm22_receiveStatus,
|
||||
.next_state = {
|
||||
[RFM22B_EVENT_RX_COMPLETE] = RFM22B_STATE_SENDING_ACK,
|
||||
[RFM22B_EVENT_TIMEOUT] = RFM22B_STATE_TIMEOUT,
|
||||
[RFM22B_EVENT_ERROR] = RFM22B_STATE_ERROR,
|
||||
[RFM22B_EVENT_INITIALIZE] = RFM22B_STATE_INITIALIZING,
|
||||
[RFM22B_EVENT_FATAL_ERROR] = RFM22B_STATE_FATAL_ERROR,
|
||||
},
|
||||
},
|
||||
@ -410,6 +367,7 @@ const static struct pios_rfm22b_transition rfm22b_transitions[RFM22B_STATE_NUM_S
|
||||
[RFM22B_EVENT_RX_MODE] = RFM22B_STATE_RX_MODE,
|
||||
[RFM22B_EVENT_TIMEOUT] = RFM22B_STATE_TIMEOUT,
|
||||
[RFM22B_EVENT_ERROR] = RFM22B_STATE_ERROR,
|
||||
[RFM22B_EVENT_INITIALIZE] = RFM22B_STATE_INITIALIZING,
|
||||
[RFM22B_EVENT_FATAL_ERROR] = RFM22B_STATE_FATAL_ERROR,
|
||||
},
|
||||
},
|
||||
@ -417,9 +375,41 @@ const static struct pios_rfm22b_transition rfm22b_transitions[RFM22B_STATE_NUM_S
|
||||
.entry_fn = rfm22_txData,
|
||||
.next_state = {
|
||||
[RFM22B_EVENT_INT_RECEIVED] = RFM22B_STATE_TX_DATA,
|
||||
[RFM22B_EVENT_TX_COMPLETE] = RFM22B_STATE_TX_START,
|
||||
[RFM22B_EVENT_RX_MODE] = RFM22B_STATE_RX_MODE,
|
||||
[RFM22B_EVENT_FAILURE] = RFM22B_STATE_TX_FAILURE,
|
||||
[RFM22B_EVENT_TIMEOUT] = RFM22B_STATE_TIMEOUT,
|
||||
[RFM22B_EVENT_ERROR] = RFM22B_STATE_ERROR,
|
||||
[RFM22B_EVENT_INITIALIZE] = RFM22B_STATE_INITIALIZING,
|
||||
[RFM22B_EVENT_FATAL_ERROR] = RFM22B_STATE_FATAL_ERROR,
|
||||
},
|
||||
},
|
||||
[RFM22B_STATE_TX_FAILURE] = {
|
||||
.entry_fn = rfm22_txFailure,
|
||||
.next_state = {
|
||||
[RFM22B_EVENT_TX_START] = RFM22B_STATE_TX_START,
|
||||
[RFM22B_EVENT_TIMEOUT] = RFM22B_STATE_TIMEOUT,
|
||||
[RFM22B_EVENT_ERROR] = RFM22B_STATE_ERROR,
|
||||
[RFM22B_EVENT_INITIALIZE] = RFM22B_STATE_INITIALIZING,
|
||||
[RFM22B_EVENT_FATAL_ERROR] = RFM22B_STATE_FATAL_ERROR,
|
||||
},
|
||||
},
|
||||
[RFM22B_STATE_SENDING_ACK] = {
|
||||
.entry_fn = rfm22_sendAck,
|
||||
.next_state = {
|
||||
[RFM22B_EVENT_TX_START] = RFM22B_STATE_TX_START,
|
||||
[RFM22B_EVENT_INITIALIZE] = RFM22B_STATE_INITIALIZING,
|
||||
[RFM22B_EVENT_ERROR] = RFM22B_STATE_ERROR,
|
||||
[RFM22B_EVENT_INITIALIZE] = RFM22B_STATE_INITIALIZING,
|
||||
[RFM22B_EVENT_FATAL_ERROR] = RFM22B_STATE_FATAL_ERROR,
|
||||
},
|
||||
},
|
||||
[RFM22B_STATE_SENDING_NACK] = {
|
||||
.entry_fn = rfm22_sendNack,
|
||||
.next_state = {
|
||||
[RFM22B_EVENT_TX_START] = RFM22B_STATE_TX_START,
|
||||
[RFM22B_EVENT_INITIALIZE] = RFM22B_STATE_INITIALIZING,
|
||||
[RFM22B_EVENT_ERROR] = RFM22B_STATE_ERROR,
|
||||
[RFM22B_EVENT_INITIALIZE] = RFM22B_STATE_INITIALIZING,
|
||||
[RFM22B_EVENT_FATAL_ERROR] = RFM22B_STATE_FATAL_ERROR,
|
||||
},
|
||||
},
|
||||
@ -429,6 +419,7 @@ const static struct pios_rfm22b_transition rfm22b_transitions[RFM22B_STATE_NUM_S
|
||||
[RFM22B_EVENT_TX_START] = RFM22B_STATE_TX_START,
|
||||
[RFM22B_EVENT_INITIALIZE] = RFM22B_STATE_INITIALIZING,
|
||||
[RFM22B_EVENT_ERROR] = RFM22B_STATE_ERROR,
|
||||
[RFM22B_EVENT_INITIALIZE] = RFM22B_STATE_INITIALIZING,
|
||||
[RFM22B_EVENT_FATAL_ERROR] = RFM22B_STATE_FATAL_ERROR,
|
||||
},
|
||||
},
|
||||
@ -437,14 +428,13 @@ const static struct pios_rfm22b_transition rfm22b_transitions[RFM22B_STATE_NUM_S
|
||||
.next_state = {
|
||||
[RFM22B_EVENT_INITIALIZE] = RFM22B_STATE_INITIALIZING,
|
||||
[RFM22B_EVENT_ERROR] = RFM22B_STATE_ERROR,
|
||||
[RFM22B_EVENT_INITIALIZE] = RFM22B_STATE_INITIALIZING,
|
||||
[RFM22B_EVENT_FATAL_ERROR] = RFM22B_STATE_FATAL_ERROR,
|
||||
},
|
||||
},
|
||||
[RFM22B_STATE_FATAL_ERROR] = {
|
||||
.entry_fn = rfm22_fatal_error,
|
||||
.next_state = {
|
||||
[RFM22B_EVENT_ERROR] = RFM22B_STATE_ERROR,
|
||||
[RFM22B_EVENT_FATAL_ERROR] = RFM22B_STATE_FATAL_ERROR,
|
||||
},
|
||||
},
|
||||
};
|
||||
@ -509,7 +499,15 @@ static const uint8_t ss_reg_70[] = { 0x24, 0x2D}; // rfm22_modulation_mode_cont
|
||||
static const uint8_t ss_reg_71[] = { 0x2B, 0x23}; // rfm22_modulation_mode_control2
|
||||
|
||||
|
||||
static bool PIOS_RFM22B_validate(struct pios_rfm22b_dev * rfm22b_dev)
|
||||
static inline uint32_t timeDifferenceMs(portTickType start_time, portTickType end_time)
|
||||
{
|
||||
if(end_time >= start_time)
|
||||
return (end_time - start_time) * portTICK_RATE_MS;
|
||||
// Rollover
|
||||
return ((portMAX_DELAY - start_time) + end_time) * portTICK_RATE_MS;
|
||||
}
|
||||
|
||||
bool PIOS_RFM22B_validate(struct pios_rfm22b_dev * rfm22b_dev)
|
||||
{
|
||||
return (rfm22b_dev != NULL && rfm22b_dev->magic == PIOS_RFM22B_DEV_MAGIC);
|
||||
}
|
||||
@ -557,72 +555,45 @@ int32_t PIOS_RFM22B_Init(uint32_t *rfm22b_id, uint32_t spi_id, uint32_t slave_nu
|
||||
struct pios_rfm22b_dev * rfm22b_dev = (struct pios_rfm22b_dev *) PIOS_RFM22B_alloc();
|
||||
if (!rfm22b_dev)
|
||||
return(-1);
|
||||
*rfm22b_id = (uint32_t)rfm22b_dev;
|
||||
g_rfm22b_dev = rfm22b_dev;
|
||||
|
||||
// Store the SPI handle
|
||||
rfm22b_dev->slave_num = slave_num;
|
||||
rfm22b_dev->spi_id = spi_id;
|
||||
|
||||
// Set the state to initializing.
|
||||
rfm22b_dev->state = RFM22B_STATE_UNINITIALIZED;
|
||||
// Initialize our configuration parameters
|
||||
rfm22b_dev->coordinator = false;
|
||||
rfm22b_dev->send_ppm = false;
|
||||
rfm22b_dev->datarate = RFM22B_DEFAULT_RX_DATARATE;
|
||||
|
||||
// Initialize the com callbacks.
|
||||
rfm22b_dev->com_config_cb = NULL;
|
||||
rfm22b_dev->rx_in_cb = NULL;
|
||||
rfm22b_dev->tx_out_cb = NULL;
|
||||
|
||||
// Initialize the stats.
|
||||
rfm22b_dev->stats.packets_per_sec = 0;
|
||||
rfm22b_dev->stats.rx_good = 0;
|
||||
rfm22b_dev->stats.rx_corrected = 0;
|
||||
rfm22b_dev->stats.rx_error = 0;
|
||||
rfm22b_dev->stats.rx_missed = 0;
|
||||
rfm22b_dev->stats.tx_dropped = 0;
|
||||
rfm22b_dev->stats.tx_resent = 0;
|
||||
rfm22b_dev->stats.resets = 0;
|
||||
rfm22b_dev->stats.timeouts = 0;
|
||||
rfm22b_dev->stats.link_quality = 0;
|
||||
rfm22b_dev->stats.rssi = 0;
|
||||
|
||||
// Create the event queue
|
||||
rfm22b_dev->eventQueue = xQueueCreate(EVENT_QUEUE_SIZE, sizeof(enum pios_rfm22b_event));
|
||||
|
||||
// Initialize the register values.
|
||||
rfm22b_dev->device_status = 0;
|
||||
rfm22b_dev->int_status1 = 0;
|
||||
rfm22b_dev->int_status2 = 0;
|
||||
rfm22b_dev->ezmac_status = 0;
|
||||
|
||||
// Initlize the link stats.
|
||||
rfm22b_dev->slow_block = 0;
|
||||
rfm22b_dev->fast_block = 0;
|
||||
rfm22b_dev->slow_good_packets = 0;
|
||||
rfm22b_dev->fast_good_packets = 0;
|
||||
rfm22b_dev->slow_corrected_packets = 0;
|
||||
rfm22b_dev->fast_corrected_packets = 0;
|
||||
rfm22b_dev->slow_error_packets = 0;
|
||||
rfm22b_dev->fast_error_packets = 0;
|
||||
rfm22b_dev->slow_link_quality = 255;
|
||||
rfm22b_dev->fast_link_quality = 255;
|
||||
|
||||
// Initialize the stats.
|
||||
rfm22b_dev->resets = 0;
|
||||
rfm22b_dev->timeouts = 0;
|
||||
rfm22b_dev->errors = 0;
|
||||
rfm22b_dev->tx_packet_count = 0;
|
||||
rfm22b_dev->rx_packet_count = 0;
|
||||
rfm22b_dev->rssi = 0;
|
||||
rfm22b_dev->rssi_dBm = -127;
|
||||
|
||||
// Bind the configuration to the device instance
|
||||
rfm22b_dev->cfg = *cfg;
|
||||
rfm22b_dev->datarate = RFM22B_DEFAULT_RX_DATARATE;
|
||||
|
||||
// Initialize the packets.
|
||||
rfm22b_dev->rx_packet = NULL;
|
||||
rfm22b_dev->rx_packet_next = NULL;
|
||||
rfm22b_dev->rx_packet_prev = NULL;
|
||||
rfm22b_dev->rx_packet_len = 0;
|
||||
rfm22b_dev->tx_packet = NULL;
|
||||
|
||||
*rfm22b_id = (uint32_t)rfm22b_dev;
|
||||
g_rfm22b_dev = rfm22b_dev;
|
||||
|
||||
// Calculate the (approximate) maximum amount of time that it should take to transmit / receive a packet.
|
||||
rfm22b_dev->packet_start_ticks = 0;
|
||||
|
||||
// Create a semaphore to know if an ISR needs responding to
|
||||
vSemaphoreCreateBinary( rfm22b_dev->isrPending );
|
||||
|
||||
// Create a semaphore to know when an rx packet is available
|
||||
vSemaphoreCreateBinary( rfm22b_dev->rxsem );
|
||||
|
||||
// Create the packet queue.
|
||||
rfm22b_dev->packetQueue = xQueueCreate(PACKET_QUEUE_SIZE, sizeof(PHPacketHandle));
|
||||
|
||||
// Initialize the max tx power level.
|
||||
PIOS_RFM22B_SetTxPower(*rfm22b_id, cfg->maxTxPower);
|
||||
|
||||
// Create our (hopefully) unique 32 bit id from the processor serial number.
|
||||
uint8_t crcs[] = { 0, 0, 0, 0 };
|
||||
{
|
||||
@ -643,12 +614,18 @@ int32_t PIOS_RFM22B_Init(uint32_t *rfm22b_id, uint32_t spi_id, uint32_t slave_nu
|
||||
PIOS_WDG_RegisterFlag(PIOS_WDG_RFM22B);
|
||||
#endif /* PIOS_WDG_RFM22B */
|
||||
|
||||
// Start the driver task. This task controls the radio state machine and removed all of the IO from the IRQ handler.
|
||||
xTaskCreate(PIOS_RFM22B_Task, (signed char *)"PIOS_RFM22B_Task", STACK_SIZE_BYTES, (void*)rfm22b_dev, TASK_PRIORITY, &(rfm22b_dev->taskHandle));
|
||||
// Initialize the ECC library.
|
||||
initialize_ecc();
|
||||
|
||||
// Set the state to initializing.
|
||||
rfm22b_dev->state = RFM22B_STATE_UNINITIALIZED;
|
||||
|
||||
// Initialize the radio device.
|
||||
PIOS_RFM22B_InjectEvent(rfm22b_dev, RFM22B_EVENT_INITIALIZE, false);
|
||||
|
||||
// Start the driver task. This task controls the radio state machine and removed all of the IO from the IRQ handler.
|
||||
xTaskCreate(PIOS_RFM22B_Task, (signed char *)"PIOS_RFM22B_Task", STACK_SIZE_BYTES, (void*)rfm22b_dev, TASK_PRIORITY, &(rfm22b_dev->taskHandle));
|
||||
|
||||
return(0);
|
||||
}
|
||||
|
||||
@ -671,7 +648,7 @@ bool PIOS_RFM22_EXT_Int(void)
|
||||
* \param[in] event The event to inject
|
||||
* \param[in] inISR Is this being called from an interrrup service routine?
|
||||
*/
|
||||
static void PIOS_RFM22B_InjectEvent(struct pios_rfm22b_dev *rfm22b_dev, enum pios_rfm22b_event event, bool inISR)
|
||||
void PIOS_RFM22B_InjectEvent(struct pios_rfm22b_dev *rfm22b_dev, enum pios_rfm22b_event event, bool inISR)
|
||||
{
|
||||
|
||||
// Store the event.
|
||||
@ -697,184 +674,172 @@ static void PIOS_RFM22B_InjectEvent(struct pios_rfm22b_dev *rfm22b_dev, enum pio
|
||||
}
|
||||
|
||||
/**
|
||||
* Returns the unique device ID for th RFM22B device.
|
||||
* Returns the unique device ID for the RFM22B device.
|
||||
* \param[in] rfm22b_id The RFM22B device index.
|
||||
* \return The unique device ID
|
||||
*/
|
||||
uint32_t PIOS_RFM22B_DeviceID(uint32_t rfm22b_id)
|
||||
{
|
||||
struct pios_rfm22b_dev *rfm22b_dev = (struct pios_rfm22b_dev *)rfm22b_id;
|
||||
if(PIOS_RFM22B_validate(rfm22b_dev))
|
||||
if (PIOS_RFM22B_validate(rfm22b_dev))
|
||||
return rfm22b_dev->deviceID;
|
||||
else
|
||||
return 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* Sets the radio device transmit power.
|
||||
* \param[in] rfm22b_id The RFM22B device index.
|
||||
* \param[in] tx_pwr The transmit power.
|
||||
*/
|
||||
void PIOS_RFM22B_SetTxPower(uint32_t rfm22b_id, enum rfm22b_tx_power tx_pwr)
|
||||
{
|
||||
struct pios_rfm22b_dev *rfm22b_dev = (struct pios_rfm22b_dev *)rfm22b_id;
|
||||
if(!PIOS_RFM22B_validate(rfm22b_dev))
|
||||
if (!PIOS_RFM22B_validate(rfm22b_dev))
|
||||
return;
|
||||
rfm22b_dev->tx_power = tx_pwr;
|
||||
}
|
||||
|
||||
void PIOS_RFM22B_SetDestinationId(uint32_t rfm22b_id, uint32_t dest_id)
|
||||
/**
|
||||
* Sets the radio frequency range and value.
|
||||
* \param[in] rfm22b_id The RFM22B device index.
|
||||
* \param[in] min_frequency The minimum frequency.
|
||||
* \param[in] max_frequency The maximum frequency.
|
||||
*/
|
||||
void PIOS_RFM22B_SetFrequencyRange(uint32_t rfm22b_id, uint32_t min_frequency, uint32_t max_frequency)
|
||||
{
|
||||
struct pios_rfm22b_dev *rfm22b_dev = (struct pios_rfm22b_dev *)rfm22b_id;
|
||||
if(!PIOS_RFM22B_validate(rfm22b_dev))
|
||||
if (!PIOS_RFM22B_validate(rfm22b_dev))
|
||||
return;
|
||||
rfm22b_dev->destination_id = (dest_id == 0) ? 0xffffffff : dest_id;
|
||||
}
|
||||
|
||||
uint16_t PIOS_RFM22B_Resets(uint32_t rfm22b_id)
|
||||
{
|
||||
struct pios_rfm22b_dev *rfm22b_dev = (struct pios_rfm22b_dev *)rfm22b_id;
|
||||
if(!PIOS_RFM22B_validate(rfm22b_dev))
|
||||
return 0;
|
||||
return rfm22b_dev->resets;
|
||||
}
|
||||
|
||||
uint16_t PIOS_RFM22B_Timeouts(uint32_t rfm22b_id)
|
||||
{
|
||||
struct pios_rfm22b_dev *rfm22b_dev = (struct pios_rfm22b_dev *)rfm22b_id;
|
||||
if(!PIOS_RFM22B_validate(rfm22b_dev))
|
||||
return 0;
|
||||
return rfm22b_dev->timeouts;
|
||||
}
|
||||
|
||||
uint8_t PIOS_RFM22B_LinkQuality(uint32_t rfm22b_id)
|
||||
{
|
||||
struct pios_rfm22b_dev *rfm22b_dev = (struct pios_rfm22b_dev *)rfm22b_id;
|
||||
if(!PIOS_RFM22B_validate(rfm22b_dev))
|
||||
return 0;
|
||||
return rfm22b_dev->slow_link_quality;
|
||||
}
|
||||
|
||||
int8_t PIOS_RFM22B_RSSI(uint32_t rfm22b_id)
|
||||
{
|
||||
struct pios_rfm22b_dev *rfm22b_dev = (struct pios_rfm22b_dev *)rfm22b_id;
|
||||
if(!PIOS_RFM22B_validate(rfm22b_dev))
|
||||
return 0;
|
||||
return rfm22b_dev->rssi_dBm;
|
||||
}
|
||||
|
||||
static void PIOS_RFM22B_RxStart(uint32_t rfm22b_id, uint16_t rx_bytes_avail)
|
||||
{
|
||||
struct pios_rfm22b_dev * rfm22b_dev = (struct pios_rfm22b_dev *)rfm22b_id;
|
||||
|
||||
bool valid = PIOS_RFM22B_validate(rfm22b_dev);
|
||||
PIOS_Assert(valid);
|
||||
|
||||
rfm22b_dev->min_frequency = min_frequency;
|
||||
rfm22b_dev->max_frequency = max_frequency;
|
||||
rfm22_setNominalCarrierFrequency(rfm22b_dev, (max_frequency - min_frequency) / 2);
|
||||
}
|
||||
|
||||
/**
|
||||
* Insert a packet on the packet queue for sending.
|
||||
* Note: If this finction succedds, the packet will be released by the driver, so no release is necessary.
|
||||
* If this function doesn't success, the caller is still responsible for the packet.
|
||||
* \param[in] rfm22b_id The rfm22b device.
|
||||
* \param[in] p The packet handle.
|
||||
* \param[in] max_delay The maximum time to delay waiting to queue the packet.
|
||||
* \return true on success, false on failue to queue the packet.
|
||||
* Sets the radio destination ID.
|
||||
* \param[in] rfm22b_id The RFM22B device index.
|
||||
* \param[in] dest_id The destination ID.
|
||||
*/
|
||||
bool PIOS_RFM22B_Send_Packet(uint32_t rfm22b_id, PHPacketHandle p, uint32_t max_delay)
|
||||
void PIOS_RFM22B_SetDestinationId(uint32_t rfm22b_id, uint32_t dest_id)
|
||||
{
|
||||
struct pios_rfm22b_dev *rfm22b_dev = (struct pios_rfm22b_dev *)rfm22b_id;
|
||||
if (!PIOS_RFM22B_validate(rfm22b_dev))
|
||||
return;
|
||||
rfm22b_dev->destination_id = (dest_id == 0) ? 0xffffffff : dest_id;
|
||||
// The first slot is reserved for our current pairID
|
||||
rfm22b_dev->pair_stats[0].pairID = dest_id;
|
||||
rfm22b_dev->pair_stats[0].rssi = -127;
|
||||
rfm22b_dev->pair_stats[0].afc_correction = 0;
|
||||
rfm22b_dev->pair_stats[0].lastContact = 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* Configures the radio as a coordinator or not.
|
||||
* \param[in] rfm22b_id The RFM22B device index.
|
||||
* \param[in] coordinator Sets as coordinator if true.
|
||||
*/
|
||||
void PIOS_RFM22B_SetCoordinator(uint32_t rfm22b_id, bool coordinator)
|
||||
{
|
||||
struct pios_rfm22b_dev *rfm22b_dev = (struct pios_rfm22b_dev *)rfm22b_id;
|
||||
if (!PIOS_RFM22B_validate(rfm22b_dev))
|
||||
return;
|
||||
rfm22b_dev->coordinator = coordinator;
|
||||
|
||||
// Re-initialize the radio device.
|
||||
PIOS_RFM22B_InjectEvent(rfm22b_dev, RFM22B_EVENT_INITIALIZE, false);
|
||||
}
|
||||
|
||||
/**
|
||||
* Set the remote com port configuration parameters.
|
||||
* \param[in] rfm22b_id The rfm22b device.
|
||||
* \param[in] com_port The remote com port
|
||||
* \param[in] com_speed The remote com port speed
|
||||
*/
|
||||
void PIOS_RFM22B_SetRemoteComConfig(uint32_t rfm22b_id, OPLinkSettingsOutputConnectionOptions com_port, OPLinkSettingsComSpeedOptions com_speed)
|
||||
{
|
||||
struct pios_rfm22b_dev *rfm22b_dev = (struct pios_rfm22b_dev *)rfm22b_id;
|
||||
if(!PIOS_RFM22B_validate(rfm22b_dev))
|
||||
return;
|
||||
rfm22b_dev->con_packet.port = com_port;
|
||||
rfm22b_dev->con_packet.com_speed = com_speed;
|
||||
}
|
||||
|
||||
/**
|
||||
* Set the com port configuration callback (to receive com configuration over the air)
|
||||
* \param[in] rfm22b_id The rfm22b device.
|
||||
* \param[in] cb A pointer to the callback function
|
||||
*/
|
||||
void PIOS_RFM22B_SetComConfigCallback(uint32_t rfm22b_id, PIOS_RFM22B_ComConfigCallback cb)
|
||||
{
|
||||
struct pios_rfm22b_dev *rfm22b_dev = (struct pios_rfm22b_dev *)rfm22b_id;
|
||||
if(!PIOS_RFM22B_validate(rfm22b_dev))
|
||||
return;
|
||||
rfm22b_dev->com_config_cb = cb;
|
||||
}
|
||||
|
||||
/**
|
||||
* Returns the device statistics RFM22B device.
|
||||
* \param[in] rfm22b_id The RFM22B device index.
|
||||
* \param[out] stats The stats are returned in this structure
|
||||
*/
|
||||
void PIOS_RFM22B_GetStats(uint32_t rfm22b_id, struct rfm22b_stats *stats) {
|
||||
struct pios_rfm22b_dev *rfm22b_dev = (struct pios_rfm22b_dev *)rfm22b_id;
|
||||
if(!PIOS_RFM22B_validate(rfm22b_dev))
|
||||
return;
|
||||
|
||||
// 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;
|
||||
}
|
||||
}
|
||||
*stats = rfm22b_dev->stats;
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the stats of the oter radio devices that are in range.
|
||||
* \param[out] device_ids A pointer to the array to store the device IDs.
|
||||
* \param[out] RSSIs A pointer to the array to store the RSSI values in.
|
||||
* \param[in] mx_pairs The length of the pdevice_ids and RSSIs arrays.
|
||||
* \return The number of pair stats returned.
|
||||
*/
|
||||
uint8_t PIOS_RFM2B_GetPairStats(uint32_t rfm22b_id, uint32_t *device_ids, int8_t *RSSIs, uint8_t max_pairs)
|
||||
{
|
||||
struct pios_rfm22b_dev *rfm22b_dev = (struct pios_rfm22b_dev *)rfm22b_id;
|
||||
if (!PIOS_RFM22B_validate(rfm22b_dev))
|
||||
return 0;
|
||||
|
||||
uint8_t mp = (max_pairs >= OPLINKSTATUS_PAIRIDS_NUMELEM) ? max_pairs : OPLINKSTATUS_PAIRIDS_NUMELEM;
|
||||
for (uint8_t i = 0; i < mp; ++i)
|
||||
{
|
||||
device_ids[i] = rfm22b_dev->pair_stats[i].pairID;
|
||||
RSSIs[i] = rfm22b_dev->pair_stats[i].rssi;
|
||||
}
|
||||
|
||||
return mp;
|
||||
}
|
||||
|
||||
/**
|
||||
* Check the radio device for a valid connection
|
||||
* \param[in] rfm22b_id The rfm22b device.
|
||||
* Returns true if there is a valid connection to paired radio, false otherwise.
|
||||
*/
|
||||
bool PIOS_RFM22B_LinkStatus(uint32_t rfm22b_id)
|
||||
{
|
||||
struct pios_rfm22b_dev *rfm22b_dev = (struct pios_rfm22b_dev *)rfm22b_id;
|
||||
if(!PIOS_RFM22B_validate(rfm22b_dev))
|
||||
return false;
|
||||
|
||||
// Store the packet handle in the packet queue
|
||||
if (xQueueSend(rfm22b_dev->packetQueue, &p, max_delay) != pdTRUE)
|
||||
return false;
|
||||
|
||||
// Inject a send packet event
|
||||
PIOS_RFM22B_InjectEvent(g_rfm22b_dev, RFM22B_EVENT_SEND_PACKET, false);
|
||||
|
||||
// Success
|
||||
return true;
|
||||
}
|
||||
|
||||
/**
|
||||
* Receive a packet from the radio.
|
||||
* \param[in] rfm22b_id The rfm22b device.
|
||||
* \param[in] pret A pointer to the packet handle.
|
||||
* \param[in] max_delay The maximum time to delay waiting for a packet.
|
||||
* \return The number of bytes received.
|
||||
*/
|
||||
uint32_t PIOS_RFM22B_Receive_Packet(uint32_t rfm22b_id, PHPacketHandle *pret, uint32_t max_delay)
|
||||
{
|
||||
struct pios_rfm22b_dev * rfm22b_dev = (struct pios_rfm22b_dev *)rfm22b_id;
|
||||
if (!PIOS_RFM22B_validate(rfm22b_dev))
|
||||
return 0;
|
||||
|
||||
// Allocate the next Rx packet
|
||||
if (rfm22b_dev->rx_packet_next == NULL)
|
||||
rfm22b_dev->rx_packet_next = PHGetRXPacket(pios_packet_handler);
|
||||
|
||||
// Block on the semephore until the a packet has been received.
|
||||
if (xSemaphoreTake(rfm22b_dev->rxsem, max_delay / portTICK_RATE_MS) != pdTRUE)
|
||||
return 0;
|
||||
|
||||
// Return the Rx packet if it's available.
|
||||
uint32_t rx_len = 0;
|
||||
if (rfm22b_dev->rx_packet_prev)
|
||||
{
|
||||
PHPacketHandle p = rfm22b_dev->rx_packet_prev;
|
||||
uint16_t len = PHPacketSizeECC(p);
|
||||
|
||||
// Attempt to correct any errors in the packet.
|
||||
decode_data((unsigned char*)p, len);
|
||||
|
||||
// Check if there were any errors
|
||||
bool rx_error = check_syndrome() != 0;
|
||||
if(rx_error)
|
||||
{
|
||||
|
||||
// We have an error. Try to correct it.
|
||||
if (correct_errors_erasures((unsigned char*)p, len, 0, 0) == 0)
|
||||
{
|
||||
// We couldn't correct the error, so drop the packet.
|
||||
rfm22b_dev->fast_error_packets++;
|
||||
PHReleaseRXPacket(pios_packet_handler, p);
|
||||
}
|
||||
else
|
||||
{
|
||||
// We corrected the error.
|
||||
rfm22b_dev->fast_corrected_packets++;
|
||||
rx_error = false;
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
// Return the packet if there were not uncorrectable errors.
|
||||
if (!rx_error)
|
||||
{
|
||||
rfm22b_dev->fast_good_packets++;
|
||||
*pret = p;
|
||||
rx_len = rfm22b_dev->rx_packet_len;
|
||||
|
||||
// Update the link statistics if necessary.
|
||||
uint8_t fast_block = (p->header.seq_num >> 2) & 0xff;
|
||||
uint8_t slow_block = (p->header.seq_num >> 4) & 0xff;
|
||||
if (rfm22b_dev->fast_block != fast_block)
|
||||
{
|
||||
rfm22b_dev->fast_link_quality = (uint8_t)(((4 + (uint16_t)rfm22b_dev->fast_good_packets - rfm22b_dev->fast_error_packets) << 5) - 1);
|
||||
rfm22b_dev->slow_good_packets += rfm22b_dev->fast_good_packets;
|
||||
rfm22b_dev->slow_corrected_packets += rfm22b_dev->fast_corrected_packets;
|
||||
rfm22b_dev->slow_error_packets += rfm22b_dev->fast_error_packets;
|
||||
rfm22b_dev->fast_good_packets = rfm22b_dev->fast_corrected_packets = rfm22b_dev->fast_error_packets = 0;
|
||||
rfm22b_dev->fast_block = fast_block;
|
||||
}
|
||||
if (rfm22b_dev->slow_block != slow_block)
|
||||
{
|
||||
rfm22b_dev->slow_link_quality = (uint8_t)(((16 + (uint16_t)rfm22b_dev->slow_good_packets - rfm22b_dev->slow_error_packets) << 3) - 1);
|
||||
rfm22b_dev->slow_good_packets = rfm22b_dev->slow_corrected_packets = rfm22b_dev->slow_error_packets = 0;
|
||||
rfm22b_dev->slow_block = slow_block;
|
||||
}
|
||||
}
|
||||
rfm22b_dev->rx_packet_prev = NULL;
|
||||
}
|
||||
|
||||
return rx_len;
|
||||
return (rfm22b_dev->stats.link_state == OPLINKSTATUS_LINKSTATE_CONNECTED) && (rfm22b_dev->stats.link_quality > RFM22B_LINK_QUALITY_THRESHOLD);
|
||||
}
|
||||
|
||||
/**
|
||||
@ -887,6 +852,7 @@ static void PIOS_RFM22B_Task(void *parameters)
|
||||
return;
|
||||
portTickType lastEventTicks = xTaskGetTickCount();
|
||||
portTickType lastStatusTicks = lastEventTicks;
|
||||
portTickType lastPPMTicks = lastEventTicks;
|
||||
|
||||
while(1)
|
||||
{
|
||||
@ -896,7 +862,7 @@ static void PIOS_RFM22B_Task(void *parameters)
|
||||
#endif /* PIOS_WDG_RFM22B */
|
||||
|
||||
// Wait for a signal indicating an external interrupt or a pending send/receive request.
|
||||
if ( xSemaphoreTake(g_rfm22b_dev->isrPending, ISR_TIMEOUT / portTICK_RATE_MS) == pdTRUE ) {
|
||||
if (xSemaphoreTake(rfm22b_dev->isrPending, ISR_TIMEOUT / portTICK_RATE_MS) == pdTRUE) {
|
||||
lastEventTicks = xTaskGetTickCount();
|
||||
|
||||
// Process events through the state machine.
|
||||
@ -906,154 +872,197 @@ static void PIOS_RFM22B_Task(void *parameters)
|
||||
if ((event == RFM22B_EVENT_INT_RECEIVED) &&
|
||||
((rfm22b_dev->state == RFM22B_STATE_UNINITIALIZED) || (rfm22b_dev->state == RFM22B_STATE_INITIALIZING)))
|
||||
continue;
|
||||
|
||||
// Process all state transitions.
|
||||
while(event != RFM22B_EVENT_NUM_EVENTS)
|
||||
event = rfm22_process_state_transition(rfm22b_dev, event);
|
||||
rfm22_process_event(rfm22b_dev, event);
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
// Has it been too long since the last event?
|
||||
portTickType curTicks = xTaskGetTickCount();
|
||||
if (curTicks < lastEventTicks)
|
||||
lastEventTicks = curTicks;
|
||||
portTickType ticksSinceEvent = curTicks - lastEventTicks;
|
||||
if ((ticksSinceEvent / portTICK_RATE_MS) > PIOS_RFM22B_SUPERVISOR_TIMEOUT)
|
||||
if (timeDifferenceMs(lastEventTicks, curTicks) > PIOS_RFM22B_SUPERVISOR_TIMEOUT)
|
||||
{
|
||||
// Transsition through an error event.
|
||||
enum pios_rfm22b_event event = RFM22B_EVENT_ERROR;
|
||||
while(event != RFM22B_EVENT_NUM_EVENTS)
|
||||
event = rfm22_process_state_transition(rfm22b_dev, event);
|
||||
rfm22_process_event(rfm22b_dev, RFM22B_EVENT_ERROR);
|
||||
|
||||
// Clear the event queue.
|
||||
enum pios_rfm22b_event event;
|
||||
while (xQueueReceive(rfm22b_dev->eventQueue, &event, 0) == pdTRUE)
|
||||
;
|
||||
lastEventTicks = xTaskGetTickCount();
|
||||
}
|
||||
}
|
||||
|
||||
// Have we locked up sending / receiving a packet?
|
||||
if (rfm22b_dev->packet_start_ticks > 0)
|
||||
portTickType curTicks = xTaskGetTickCount();
|
||||
// Have we been sending this packet too long?
|
||||
if ((rfm22b_dev->packet_start_ticks > 0) && (timeDifferenceMs(rfm22b_dev->packet_start_ticks, curTicks) > (rfm22b_dev->max_packet_time * 3)))
|
||||
rfm22_process_event(rfm22b_dev, RFM22B_EVENT_TIMEOUT);
|
||||
|
||||
// Have it been too long since we received a packet
|
||||
else if ((rfm22b_dev->rx_complete_ticks > 0) && (timeDifferenceMs(rfm22b_dev->rx_complete_ticks, curTicks) > DISCONNECT_TIMEOUT_MS))
|
||||
rfm22_process_event(rfm22b_dev, RFM22B_EVENT_ERROR);
|
||||
|
||||
else
|
||||
{
|
||||
portTickType cur_ticks = xTaskGetTickCount();
|
||||
|
||||
// Did the clock wrap around?
|
||||
if (cur_ticks < rfm22b_dev->packet_start_ticks)
|
||||
rfm22b_dev->packet_start_ticks = (cur_ticks > 0) ? cur_ticks : 1;
|
||||
|
||||
// Have we been sending this packet too long?
|
||||
if (((cur_ticks - rfm22b_dev->packet_start_ticks) / portTICK_RATE_MS) > (rfm22b_dev->max_packet_time * 3))
|
||||
|
||||
// Are we waiting for an ACK?
|
||||
if (rfm22b_dev->prev_tx_packet)
|
||||
{
|
||||
enum pios_rfm22b_event event = RFM22B_EVENT_TIMEOUT;
|
||||
while(event != RFM22B_EVENT_NUM_EVENTS)
|
||||
event = rfm22_process_state_transition(rfm22b_dev, event);
|
||||
|
||||
// Should we resend the packet?
|
||||
if (timeDifferenceMs(rfm22b_dev->tx_complete_ticks, curTicks) > rfm22b_dev->max_ack_delay)
|
||||
{
|
||||
rfm22b_dev->tx_complete_ticks = curTicks;
|
||||
rfm22_process_event(rfm22b_dev, RFM22B_EVENT_ACK_TIMEOUT);
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
|
||||
// Queue up a PPM packet if it's time.
|
||||
if (timeDifferenceMs(lastPPMTicks, curTicks) > PPM_UPDATE_PERIOD_MS)
|
||||
{
|
||||
rfm22_sendPPM(rfm22b_dev);
|
||||
lastPPMTicks = curTicks;
|
||||
}
|
||||
|
||||
// Queue up a status packet if it's time.
|
||||
if (timeDifferenceMs(lastStatusTicks, curTicks) > RADIOSTATS_UPDATE_PERIOD_MS)
|
||||
{
|
||||
rfm22_sendStatus(rfm22b_dev);
|
||||
lastStatusTicks = curTicks;
|
||||
}
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
// Queue up a status packet if it's time.
|
||||
portTickType curTicks = xTaskGetTickCount();
|
||||
// Rollover
|
||||
if (curTicks < lastStatusTicks)
|
||||
lastStatusTicks = curTicks;
|
||||
if (((curTicks - lastStatusTicks) / portTICK_RATE_MS) > RADIOSTATS_UPDATE_PERIOD_MS)
|
||||
if (rfm22_sendStatus(rfm22b_dev))
|
||||
lastStatusTicks = curTicks;
|
||||
// Send a packet if it's our time slice
|
||||
rfm22b_dev->time_to_send = (((curTicks - rfm22b_dev->time_to_send_offset) & 0x6) == 0);
|
||||
#ifdef PIOS_RFM22B_DEBUG_ON_TELEM
|
||||
if (rfm22b_dev->time_to_send)
|
||||
D4_LED_ON;
|
||||
else
|
||||
D4_LED_OFF;
|
||||
#endif
|
||||
if (rfm22b_dev->time_to_send)
|
||||
rfm22_process_event(rfm22b_dev, RFM22B_EVENT_TX_START);
|
||||
}
|
||||
}
|
||||
|
||||
static void PIOS_RFM22B_TxStart(uint32_t rfm22b_id, uint16_t tx_bytes_avail)
|
||||
// ************************************
|
||||
// radio datarate about 19200 Baud
|
||||
// radio frequency deviation 45kHz
|
||||
// radio receiver bandwidth 67kHz.
|
||||
//
|
||||
// Carson's rule:
|
||||
// The signal bandwidth is about 2(Delta-f + fm) ..
|
||||
//
|
||||
// Delta-f = frequency deviation
|
||||
// fm = maximum frequency of the signal
|
||||
//
|
||||
// This gives 2(45 + 9.6) = 109.2kHz.
|
||||
|
||||
static void rfm22_setDatarate(struct pios_rfm22b_dev * rfm22b_dev, enum rfm22b_datarate datarate, bool data_whitening)
|
||||
{
|
||||
struct pios_rfm22b_dev * rfm22b_dev = (struct pios_rfm22b_dev *)rfm22b_id;
|
||||
bool valid = PIOS_RFM22B_validate(rfm22b_dev);
|
||||
PIOS_Assert(valid);
|
||||
uint32_t datarate_bps = data_rate[datarate];
|
||||
rfm22b_dev->max_packet_time = (uint16_t)((float)(PIOS_PH_MAX_PACKET * 8 * 1000) / (float)(datarate_bps) + 0.5);
|
||||
if (rfm22b_dev->stats.link_state == OPLINKSTATUS_LINKSTATE_CONNECTED)
|
||||
{
|
||||
// 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(PHPacketHeader) * 8 * 1000) / (float)(datarate_bps) + 0.5) * 4 + random;
|
||||
}
|
||||
else
|
||||
rfm22b_dev->max_ack_delay = CONNECT_ATTEMPT_PERIOD_MS;
|
||||
|
||||
#ifdef NEVER
|
||||
// Get some data to send
|
||||
bool need_yield = false;
|
||||
if(tx_pre_buffer_size == 0)
|
||||
tx_pre_buffer_size = (rfm22b_dev->tx_out_cb)(rfm22b_dev->tx_out_context, tx_pre_buffer,
|
||||
TX_BUFFER_SIZE, NULL, &need_yield);
|
||||
// rfm22_if_filter_bandwidth
|
||||
rfm22_write(rfm22b_dev, 0x1C, reg_1C[datarate]);
|
||||
|
||||
// Inject a send packet event
|
||||
PIOS_RFM22B_InjectEvent(g_rfm22b_dev, RFM22B_EVENT_TX_START, false);
|
||||
#endif
|
||||
// rfm22_afc_loop_gearshift_override
|
||||
rfm22_write(rfm22b_dev, 0x1D, reg_1D[datarate]);
|
||||
// RFM22_afc_timing_control
|
||||
rfm22_write(rfm22b_dev, 0x1E, reg_1E[datarate]);
|
||||
|
||||
// RFM22_clk_recovery_gearshift_override
|
||||
rfm22_write(rfm22b_dev, 0x1F, reg_1F[datarate]);
|
||||
// rfm22_clk_recovery_oversampling_ratio
|
||||
rfm22_write(rfm22b_dev, 0x20, reg_20[datarate]);
|
||||
// rfm22_clk_recovery_offset2
|
||||
rfm22_write(rfm22b_dev, 0x21, reg_21[datarate]);
|
||||
// rfm22_clk_recovery_offset1
|
||||
rfm22_write(rfm22b_dev, 0x22, reg_22[datarate]);
|
||||
// rfm22_clk_recovery_offset0
|
||||
rfm22_write(rfm22b_dev, 0x23, reg_23[datarate]);
|
||||
// rfm22_clk_recovery_timing_loop_gain1
|
||||
rfm22_write(rfm22b_dev, 0x24, reg_24[datarate]);
|
||||
// rfm22_clk_recovery_timing_loop_gain0
|
||||
rfm22_write(rfm22b_dev, 0x25, reg_25[datarate]);
|
||||
|
||||
// rfm22_afc_limiter
|
||||
rfm22_write(rfm22b_dev, 0x2A, reg_2A[datarate]);
|
||||
|
||||
// rfm22_tx_data_rate1
|
||||
rfm22_write(rfm22b_dev, 0x6E, reg_6E[datarate]);
|
||||
// rfm22_tx_data_rate0
|
||||
rfm22_write(rfm22b_dev, 0x6F, reg_6F[datarate]);
|
||||
|
||||
if (!data_whitening)
|
||||
// rfm22_modulation_mode_control1
|
||||
rfm22_write(rfm22b_dev, 0x70, reg_70[datarate] & ~RFM22_mmc1_enwhite);
|
||||
else
|
||||
// rfm22_modulation_mode_control1
|
||||
rfm22_write(rfm22b_dev, 0x70, reg_70[datarate] | RFM22_mmc1_enwhite);
|
||||
|
||||
// rfm22_modulation_mode_control2
|
||||
rfm22_write(rfm22b_dev, 0x71, reg_71[datarate]);
|
||||
|
||||
// rfm22_frequency_deviation
|
||||
rfm22_write(rfm22b_dev, 0x72, reg_72[datarate]);
|
||||
|
||||
rfm22_write(rfm22b_dev, RFM22_ook_counter_value1, 0x00);
|
||||
rfm22_write(rfm22b_dev, RFM22_ook_counter_value2, 0x00);
|
||||
}
|
||||
|
||||
/**
|
||||
* Changes the baud rate of the RFM22B peripheral without re-initialising.
|
||||
* \param[in] rfm22b_id RFM22B name (GPS, TELEM, AUX)
|
||||
* \param[in] baud Requested baud rate
|
||||
*/
|
||||
static void PIOS_RFM22B_ChangeBaud(uint32_t rfm22b_id, uint32_t baud)
|
||||
void PIOS_RFM22B_SetDatarate(uint32_t rfm22b_id, enum rfm22b_datarate datarate, bool data_whitening)
|
||||
{
|
||||
struct pios_rfm22b_dev * rfm22b_dev = (struct pios_rfm22b_dev *)rfm22b_id;
|
||||
if(!PIOS_RFM22B_validate(rfm22b_dev))
|
||||
return;
|
||||
rfm22b_dev->datarate = datarate;
|
||||
|
||||
bool valid = PIOS_RFM22B_validate(rfm22b_dev);
|
||||
PIOS_Assert(valid);
|
||||
|
||||
}
|
||||
|
||||
static void PIOS_RFM22B_RegisterRxCallback(uint32_t rfm22b_id, pios_com_callback rx_in_cb, uint32_t context)
|
||||
{
|
||||
struct pios_rfm22b_dev * rfm22b_dev = (struct pios_rfm22b_dev *)rfm22b_id;
|
||||
|
||||
bool valid = PIOS_RFM22B_validate(rfm22b_dev);
|
||||
PIOS_Assert(valid);
|
||||
|
||||
/*
|
||||
* Order is important in these assignments since ISR uses _cb
|
||||
* field to determine if it's ok to dereference _cb and _context
|
||||
*/
|
||||
rfm22b_dev->rx_in_context = context;
|
||||
rfm22b_dev->rx_in_cb = rx_in_cb;
|
||||
}
|
||||
|
||||
static void PIOS_RFM22B_RegisterTxCallback(uint32_t rfm22b_id, pios_com_callback tx_out_cb, uint32_t context)
|
||||
{
|
||||
struct pios_rfm22b_dev * rfm22b_dev = (struct pios_rfm22b_dev *)rfm22b_id;
|
||||
|
||||
bool valid = PIOS_RFM22B_validate(rfm22b_dev);
|
||||
PIOS_Assert(valid);
|
||||
|
||||
/*
|
||||
* Order is important in these assignments since ISR uses _cb
|
||||
* field to determine if it's ok to dereference _cb and _context
|
||||
*/
|
||||
rfm22b_dev->tx_out_context = context;
|
||||
rfm22b_dev->tx_out_cb = tx_out_cb;
|
||||
// Re-initialize the radio device.
|
||||
PIOS_RFM22B_InjectEvent(rfm22b_dev, RFM22B_EVENT_INITIALIZE, false);
|
||||
}
|
||||
|
||||
// ************************************
|
||||
// SPI read/write
|
||||
|
||||
//! Assert the CS line
|
||||
static void rfm22_assertCs()
|
||||
static void rfm22_assertCs(struct pios_rfm22b_dev *rfm22b_dev)
|
||||
{
|
||||
PIOS_DELAY_WaituS(1);
|
||||
if(PIOS_RFM22B_validate(g_rfm22b_dev) && g_rfm22b_dev->spi_id != 0)
|
||||
PIOS_SPI_RC_PinSet(g_rfm22b_dev->spi_id, g_rfm22b_dev->slave_num, 0);
|
||||
if(rfm22b_dev->spi_id != 0)
|
||||
PIOS_SPI_RC_PinSet(rfm22b_dev->spi_id, rfm22b_dev->slave_num, 0);
|
||||
}
|
||||
|
||||
//! Deassert the CS line
|
||||
static void rfm22_deassertCs()
|
||||
static void rfm22_deassertCs(struct pios_rfm22b_dev *rfm22b_dev)
|
||||
{
|
||||
if(PIOS_RFM22B_validate(g_rfm22b_dev) && g_rfm22b_dev->spi_id != 0)
|
||||
PIOS_SPI_RC_PinSet(g_rfm22b_dev->spi_id, g_rfm22b_dev->slave_num, 1);
|
||||
if(rfm22b_dev->spi_id != 0)
|
||||
PIOS_SPI_RC_PinSet(rfm22b_dev->spi_id, rfm22b_dev->slave_num, 1);
|
||||
}
|
||||
|
||||
//! Claim the SPI bus semaphore
|
||||
static void rfm22_claimBus()
|
||||
static void rfm22_claimBus(struct pios_rfm22b_dev *rfm22b_dev)
|
||||
{
|
||||
if(PIOS_RFM22B_validate(g_rfm22b_dev) && g_rfm22b_dev->spi_id != 0)
|
||||
PIOS_SPI_ClaimBus(g_rfm22b_dev->spi_id);
|
||||
if(rfm22b_dev->spi_id != 0)
|
||||
PIOS_SPI_ClaimBus(rfm22b_dev->spi_id);
|
||||
}
|
||||
|
||||
//! Release the SPI bus semaphore
|
||||
static void rfm22_releaseBus()
|
||||
static void rfm22_releaseBus(struct pios_rfm22b_dev *rfm22b_dev)
|
||||
{
|
||||
if(PIOS_RFM22B_validate(g_rfm22b_dev) && g_rfm22b_dev->spi_id != 0)
|
||||
PIOS_SPI_ReleaseBus(g_rfm22b_dev->spi_id);
|
||||
if(rfm22b_dev->spi_id != 0)
|
||||
PIOS_SPI_ReleaseBus(rfm22b_dev->spi_id);
|
||||
}
|
||||
|
||||
/**
|
||||
@ -1061,16 +1070,14 @@ static void rfm22_releaseBus()
|
||||
* @param[in] addr The address to write to
|
||||
* @param[in] data The datat to write to that address
|
||||
*/
|
||||
static void rfm22_write(uint8_t addr, uint8_t data)
|
||||
static void rfm22_write(struct pios_rfm22b_dev *rfm22b_dev, uint8_t addr, uint8_t data)
|
||||
{
|
||||
if(PIOS_RFM22B_validate(g_rfm22b_dev)) {
|
||||
rfm22_claimBus();
|
||||
rfm22_assertCs();
|
||||
uint8_t buf[2] = {addr | 0x80, data};
|
||||
PIOS_SPI_TransferBlock(g_rfm22b_dev->spi_id, buf, NULL, sizeof(buf), NULL);
|
||||
rfm22_deassertCs();
|
||||
rfm22_releaseBus();
|
||||
}
|
||||
rfm22_claimBus(rfm22b_dev);
|
||||
rfm22_assertCs(rfm22b_dev);
|
||||
uint8_t buf[2] = {addr | 0x80, data};
|
||||
PIOS_SPI_TransferBlock(rfm22b_dev->spi_id, buf, NULL, sizeof(buf), NULL);
|
||||
rfm22_deassertCs(rfm22b_dev);
|
||||
rfm22_releaseBus(rfm22b_dev);
|
||||
}
|
||||
|
||||
/**
|
||||
@ -1078,14 +1085,12 @@ static void rfm22_write(uint8_t addr, uint8_t data)
|
||||
* toggle the NSS line
|
||||
* @param[in] addr The address of the RFM22b register to write
|
||||
* @param[in] data The data to write to that register
|
||||
static void rfm22_write_noclaim(uint8_t addr, uint8_t data)
|
||||
static void rfm22_write_noclaim(struct pios_rfm22b_dev *rfm22b_dev, uint8_t addr, uint8_t data)
|
||||
{
|
||||
uint8_t buf[2] = {addr | 0x80, data};
|
||||
if(PIOS_RFM22B_validate(g_rfm22b_dev)) {
|
||||
rfm22_assertCs();
|
||||
PIOS_SPI_TransferBlock(g_rfm22b_dev->spi_id, buf, NULL, sizeof(buf), NULL);
|
||||
rfm22_deassertCs();
|
||||
}
|
||||
rfm22_assertCs(rfm22b_dev);
|
||||
PIOS_SPI_TransferBlock(rfm22b_dev->spi_id, buf, NULL, sizeof(buf), NULL);
|
||||
rfm22_deassertCs(rfm22b_dev);
|
||||
}
|
||||
*/
|
||||
|
||||
@ -1095,17 +1100,15 @@ static void rfm22_write_noclaim(uint8_t addr, uint8_t data)
|
||||
* @param[in] addr The address to read from
|
||||
* @return Returns the result of the register read
|
||||
*/
|
||||
static uint8_t rfm22_read(uint8_t addr)
|
||||
static uint8_t rfm22_read(struct pios_rfm22b_dev *rfm22b_dev, uint8_t addr)
|
||||
{
|
||||
uint8_t in[2];
|
||||
uint8_t out[2] = {addr & 0x7f, 0xFF};
|
||||
if(PIOS_RFM22B_validate(g_rfm22b_dev)) {
|
||||
rfm22_claimBus();
|
||||
rfm22_assertCs();
|
||||
PIOS_SPI_TransferBlock(g_rfm22b_dev->spi_id, out, in, sizeof(out), NULL);
|
||||
rfm22_deassertCs();
|
||||
rfm22_releaseBus();
|
||||
}
|
||||
rfm22_claimBus(rfm22b_dev);
|
||||
rfm22_assertCs(rfm22b_dev);
|
||||
PIOS_SPI_TransferBlock(rfm22b_dev->spi_id, out, in, sizeof(out), NULL);
|
||||
rfm22_deassertCs(rfm22b_dev);
|
||||
rfm22_releaseBus(rfm22b_dev);
|
||||
return in[1];
|
||||
}
|
||||
|
||||
@ -1114,15 +1117,13 @@ static uint8_t rfm22_read(uint8_t addr)
|
||||
* @param[in] addr The address to read from
|
||||
* @return Returns the result of the register read
|
||||
*/
|
||||
static uint8_t rfm22_read_noclaim(uint8_t addr)
|
||||
static uint8_t rfm22_read_noclaim(struct pios_rfm22b_dev *rfm22b_dev, uint8_t addr)
|
||||
{
|
||||
uint8_t out[2] = {addr & 0x7F, 0xFF};
|
||||
uint8_t in[2];
|
||||
if (PIOS_RFM22B_validate(g_rfm22b_dev)) {
|
||||
rfm22_assertCs();
|
||||
PIOS_SPI_TransferBlock(g_rfm22b_dev->spi_id, out, in, sizeof(out), NULL);
|
||||
rfm22_deassertCs();
|
||||
}
|
||||
rfm22_assertCs(rfm22b_dev);
|
||||
PIOS_SPI_TransferBlock(rfm22b_dev->spi_id, out, in, sizeof(out), NULL);
|
||||
rfm22_deassertCs(rfm22b_dev);
|
||||
return in[1];
|
||||
}
|
||||
|
||||
@ -1159,16 +1160,21 @@ static enum pios_rfm22b_event rfm22_process_state_transition(struct pios_rfm22b_
|
||||
return RFM22B_EVENT_NUM_EVENTS;
|
||||
}
|
||||
|
||||
static void rfm22_process_event(struct pios_rfm22b_dev *rfm22b_dev, enum pios_rfm22b_event event)
|
||||
{
|
||||
// Process all state transitions.
|
||||
while(event != RFM22B_EVENT_NUM_EVENTS)
|
||||
event = rfm22_process_state_transition(rfm22b_dev, event);
|
||||
}
|
||||
|
||||
// ************************************
|
||||
|
||||
static void rfm22_setNominalCarrierFrequency(struct pios_rfm22b_dev *rfm22b_dev, uint32_t frequency_hz)
|
||||
{
|
||||
uint32_t min_frequency_hz = rfm22b_dev->cfg.minFrequencyHz;
|
||||
uint32_t max_frequency_hz = rfm22b_dev->cfg.maxFrequencyHz;
|
||||
if (frequency_hz < min_frequency_hz)
|
||||
frequency_hz = min_frequency_hz;
|
||||
else if (frequency_hz > max_frequency_hz)
|
||||
frequency_hz = max_frequency_hz;
|
||||
if (frequency_hz < rfm22b_dev->min_frequency)
|
||||
frequency_hz = rfm22b_dev->min_frequency;
|
||||
else if (frequency_hz > rfm22b_dev->max_frequency)
|
||||
frequency_hz = rfm22b_dev->max_frequency;
|
||||
|
||||
// holds the hbsel (1 or 2)
|
||||
uint8_t hbsel;
|
||||
@ -1192,126 +1198,89 @@ static void rfm22_setNominalCarrierFrequency(struct pios_rfm22b_dev *rfm22b_dev,
|
||||
rfm22b_dev->frequency_step_size = 156.25f * hbsel;
|
||||
|
||||
// frequency hopping channel (0-255)
|
||||
rfm22_write(RFM22_frequency_hopping_channel_select, rfm22b_dev->frequency_hop_channel);
|
||||
rfm22_write(rfm22b_dev, RFM22_frequency_hopping_channel_select, rfm22b_dev->frequency_hop_channel);
|
||||
|
||||
// no frequency offset
|
||||
rfm22_write(RFM22_frequency_offset1, 0);
|
||||
rfm22_write(rfm22b_dev, RFM22_frequency_offset1, 0);
|
||||
// no frequency offset
|
||||
rfm22_write(RFM22_frequency_offset2, 0);
|
||||
rfm22_write(rfm22b_dev, RFM22_frequency_offset2, 0);
|
||||
|
||||
// set the carrier frequency
|
||||
rfm22_write(RFM22_frequency_band_select, fb);
|
||||
rfm22_write(RFM22_nominal_carrier_frequency1, fc >> 8);
|
||||
rfm22_write(RFM22_nominal_carrier_frequency0, fc & 0xff);
|
||||
rfm22_write(rfm22b_dev, RFM22_frequency_band_select, fb);
|
||||
rfm22_write(rfm22b_dev, RFM22_nominal_carrier_frequency1, fc >> 8);
|
||||
rfm22_write(rfm22b_dev, RFM22_nominal_carrier_frequency0, fc & 0xff);
|
||||
}
|
||||
|
||||
void rfm22_setFreqHopChannel(uint8_t channel)
|
||||
/*
|
||||
static void rfm22_setFreqHopChannel(uint8_t channel)
|
||||
{ // set the frequency hopping channel
|
||||
g_rfm22b_dev->frequency_hop_channel = channel;
|
||||
rfm22_write(RFM22_frequency_hopping_channel_select, channel);
|
||||
rfm22_write(rfm22b_dev, RFM22_frequency_hopping_channel_select, channel);
|
||||
}
|
||||
|
||||
uint32_t rfm22_freqHopSize(void)
|
||||
static uint32_t rfm22_freqHopSize(void)
|
||||
{ // return the frequency hopping step size
|
||||
return ((uint32_t)g_rfm22b_dev->frequency_hop_step_size_reg * 10000);
|
||||
}
|
||||
|
||||
// ************************************
|
||||
// radio datarate about 19200 Baud
|
||||
// radio frequency deviation 45kHz
|
||||
// radio receiver bandwidth 67kHz.
|
||||
//
|
||||
// Carson's rule:
|
||||
// The signal bandwidth is about 2(Delta-f + fm) ..
|
||||
//
|
||||
// Delta-f = frequency deviation
|
||||
// fm = maximum frequency of the signal
|
||||
//
|
||||
// This gives 2(45 + 9.6) = 109.2kHz.
|
||||
|
||||
void RFM22_SetDatarate(uint32_t rfm22b_id, enum rfm22b_datarate datarate, bool data_whitening)
|
||||
{
|
||||
struct pios_rfm22b_dev * rfm22b_dev = (struct pios_rfm22b_dev *)rfm22b_id;
|
||||
if(!PIOS_RFM22B_validate(rfm22b_dev))
|
||||
return;
|
||||
|
||||
uint32_t datarate_bps = data_rate[datarate];
|
||||
rfm22b_dev->datarate = datarate;
|
||||
rfm22b_dev->max_packet_time = (uint16_t)((float)(PIOS_PH_MAX_PACKET * 8 * 1000) / (float)(datarate_bps) + 0.5);
|
||||
|
||||
// rfm22_if_filter_bandwidth
|
||||
rfm22_write(0x1C, reg_1C[datarate]);
|
||||
|
||||
// rfm22_afc_loop_gearshift_override
|
||||
rfm22_write(0x1D, reg_1D[datarate]);
|
||||
// RFM22_afc_timing_control
|
||||
rfm22_write(0x1E, reg_1E[datarate]);
|
||||
|
||||
// RFM22_clk_recovery_gearshift_override
|
||||
rfm22_write(0x1F, reg_1F[datarate]);
|
||||
// rfm22_clk_recovery_oversampling_ratio
|
||||
rfm22_write(0x20, reg_20[datarate]);
|
||||
// rfm22_clk_recovery_offset2
|
||||
rfm22_write(0x21, reg_21[datarate]);
|
||||
// rfm22_clk_recovery_offset1
|
||||
rfm22_write(0x22, reg_22[datarate]);
|
||||
// rfm22_clk_recovery_offset0
|
||||
rfm22_write(0x23, reg_23[datarate]);
|
||||
// rfm22_clk_recovery_timing_loop_gain1
|
||||
rfm22_write(0x24, reg_24[datarate]);
|
||||
// rfm22_clk_recovery_timing_loop_gain0
|
||||
rfm22_write(0x25, reg_25[datarate]);
|
||||
|
||||
// rfm22_afc_limiter
|
||||
rfm22_write(0x2A, reg_2A[datarate]);
|
||||
|
||||
/* This breaks all bit rates < 100000!
|
||||
if (datarate_bps < 100000)
|
||||
// rfm22_chargepump_current_trimming_override
|
||||
rfm22_write(0x58, 0x80);
|
||||
else
|
||||
// rfm22_chargepump_current_trimming_override
|
||||
rfm22_write(0x58, 0xC0);
|
||||
*/
|
||||
|
||||
// rfm22_tx_data_rate1
|
||||
rfm22_write(0x6E, reg_6E[datarate]);
|
||||
// rfm22_tx_data_rate0
|
||||
rfm22_write(0x6F, reg_6F[datarate]);
|
||||
static void rfm22_calculateLinkQuality(struct pios_rfm22b_dev *rfm22b_dev)
|
||||
{
|
||||
// Add the RX packet statistics
|
||||
rfm22b_dev->stats.rx_good = 0;
|
||||
rfm22b_dev->stats.rx_corrected = 0;
|
||||
rfm22b_dev->stats.rx_error = 0;
|
||||
rfm22b_dev->stats.tx_resent = 0;
|
||||
for (uint8_t i = 0; i < RFM22B_RX_PACKET_STATS_LEN; ++i)
|
||||
{
|
||||
uint32_t val = rfm22b_dev->rx_packet_stats[i];
|
||||
for (uint8_t j = 0; j < 16; ++j)
|
||||
{
|
||||
switch ((val >> (j * 2)) & 0x3)
|
||||
{
|
||||
case RFM22B_GOOD_RX_PACKET:
|
||||
rfm22b_dev->stats.rx_good++;
|
||||
break;
|
||||
case RFM22B_CORRECTED_RX_PACKET:
|
||||
rfm22b_dev->stats.rx_corrected++;
|
||||
break;
|
||||
case RFM22B_ERROR_RX_PACKET:
|
||||
rfm22b_dev->stats.rx_error++;
|
||||
break;
|
||||
case RFM22B_RESENT_TX_PACKET:
|
||||
rfm22b_dev->stats.tx_resent++;
|
||||
break;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// Enable data whitening
|
||||
// uint8_t txdtrtscale_bit = rfm22_read(RFM22_modulation_mode_control1) & RFM22_mmc1_txdtrtscale;
|
||||
// rfm22_write(RFM22_modulation_mode_control1, txdtrtscale_bit | RFM22_mmc1_enwhite);
|
||||
|
||||
if (!data_whitening)
|
||||
// rfm22_modulation_mode_control1
|
||||
rfm22_write(0x70, reg_70[datarate] & ~RFM22_mmc1_enwhite);
|
||||
else
|
||||
// rfm22_modulation_mode_control1
|
||||
rfm22_write(0x70, reg_70[datarate] | RFM22_mmc1_enwhite);
|
||||
|
||||
// rfm22_modulation_mode_control2
|
||||
rfm22_write(0x71, reg_71[datarate]);
|
||||
|
||||
// rfm22_frequency_deviation
|
||||
rfm22_write(0x72, reg_72[datarate]);
|
||||
|
||||
rfm22_write(RFM22_ook_counter_value1, 0x00);
|
||||
rfm22_write(RFM22_ook_counter_value2, 0x00);
|
||||
// Calculate the link quality metric, which is related to the number of good packets in relation to the number of bad packets.
|
||||
// Note: This assumes that the number of packets sampled for the stats is 64.
|
||||
// Using this equation, error and resent packets are counted as -2, and corrected packets are counted as -1.
|
||||
// The range is 0 (all error or resent packets) to 128 (all good packets).
|
||||
rfm22b_dev->stats.link_quality = 64 + rfm22b_dev->stats.rx_good - rfm22b_dev->stats.rx_error - rfm22b_dev->stats.tx_resent;
|
||||
}
|
||||
|
||||
// ************************************
|
||||
|
||||
static enum pios_rfm22b_event rfm22_setRxMode(struct pios_rfm22b_dev *rfm22b_dev)
|
||||
{
|
||||
// Are we already in Rx mode?
|
||||
if (rfm22b_dev->in_rx_mode)
|
||||
return RFM22B_EVENT_NUM_EVENTS;
|
||||
|
||||
rfm22b_dev->packet_start_ticks = 0;
|
||||
#ifdef PIOS_RFM22B_DEBUG_ON_TELEM
|
||||
D2_LED_ON;
|
||||
D3_LED_TOGGLE;
|
||||
#endif
|
||||
|
||||
// disable interrupts
|
||||
rfm22_write(RFM22_interrupt_enable1, 0x00);
|
||||
rfm22_write(RFM22_interrupt_enable2, 0x00);
|
||||
rfm22_write(rfm22b_dev, RFM22_interrupt_enable1, 0x00);
|
||||
rfm22_write(rfm22b_dev, RFM22_interrupt_enable2, 0x00);
|
||||
|
||||
// Switch to TUNE mode
|
||||
rfm22_write(RFM22_op_and_func_ctrl1, RFM22_opfc1_pllon);
|
||||
rfm22_write(rfm22b_dev, RFM22_op_and_func_ctrl1, RFM22_opfc1_pllon);
|
||||
|
||||
RX_LED_OFF;
|
||||
TX_LED_OFF;
|
||||
@ -1323,17 +1292,20 @@ static enum pios_rfm22b_event rfm22_setRxMode(struct pios_rfm22b_dev *rfm22b_dev
|
||||
rfm22b_dev->tx_data_rd = rfm22b_dev->tx_data_wr = 0;
|
||||
|
||||
// clear FIFOs
|
||||
rfm22_write(RFM22_op_and_func_ctrl2, RFM22_opfc2_ffclrrx | RFM22_opfc2_ffclrtx);
|
||||
rfm22_write(RFM22_op_and_func_ctrl2, 0x00);
|
||||
rfm22_write(rfm22b_dev, RFM22_op_and_func_ctrl2, RFM22_opfc2_ffclrrx | RFM22_opfc2_ffclrtx);
|
||||
rfm22_write(rfm22b_dev, RFM22_op_and_func_ctrl2, 0x00);
|
||||
|
||||
// enable RX interrupts
|
||||
rfm22_write(RFM22_interrupt_enable1, RFM22_ie1_encrcerror | RFM22_ie1_enpkvalid |
|
||||
rfm22_write(rfm22b_dev, RFM22_interrupt_enable1, RFM22_ie1_encrcerror | RFM22_ie1_enpkvalid |
|
||||
RFM22_ie1_enrxffafull | RFM22_ie1_enfferr);
|
||||
rfm22_write(RFM22_interrupt_enable2, RFM22_ie2_enpreainval | RFM22_ie2_enpreaval |
|
||||
rfm22_write(rfm22b_dev, RFM22_interrupt_enable2, RFM22_ie2_enpreainval | RFM22_ie2_enpreaval |
|
||||
RFM22_ie2_enswdet);
|
||||
|
||||
// enable the receiver
|
||||
rfm22_write(RFM22_op_and_func_ctrl1, RFM22_opfc1_pllon | RFM22_opfc1_rxon);
|
||||
rfm22_write(rfm22b_dev, RFM22_op_and_func_ctrl1, RFM22_opfc1_pllon | RFM22_opfc1_rxon);
|
||||
|
||||
// Indicate that we're in RX mode.
|
||||
rfm22b_dev->in_rx_mode = true;
|
||||
|
||||
// No event generated
|
||||
return RFM22B_EVENT_NUM_EVENTS;
|
||||
@ -1341,20 +1313,99 @@ static enum pios_rfm22b_event rfm22_setRxMode(struct pios_rfm22b_dev *rfm22b_dev
|
||||
|
||||
// ************************************
|
||||
|
||||
static bool rfm22_ready_to_send(struct pios_rfm22b_dev *rfm22b_dev)
|
||||
{
|
||||
// Is there a status of PPM packet ready to send?
|
||||
if (rfm22b_dev->prev_tx_packet || rfm22b_dev->send_ppm || rfm22b_dev->send_status)
|
||||
return true;
|
||||
|
||||
// Is there some data ready to sent?
|
||||
PHPacketHandle dp = &rfm22b_dev->data_packet;
|
||||
if (dp->header.data_size > 0)
|
||||
return true;
|
||||
bool need_yield = false;
|
||||
if (rfm22b_dev->tx_out_cb)
|
||||
dp->header.data_size = (rfm22b_dev->tx_out_cb)(rfm22b_dev->tx_out_context, dp->data, PH_MAX_DATA, NULL, &need_yield);
|
||||
if (dp->header.data_size > 0)
|
||||
return true;
|
||||
|
||||
return false;
|
||||
}
|
||||
|
||||
static enum pios_rfm22b_event rfm22_txStart(struct pios_rfm22b_dev *rfm22b_dev)
|
||||
{
|
||||
// See if there's a packet on the packet queue.
|
||||
PHPacketHandle p;
|
||||
if (xQueueReceive(rfm22b_dev->packetQueue, &p, 0) != pdTRUE)
|
||||
{
|
||||
// Clear the TX buffer.
|
||||
rfm22b_dev->tx_data_rd = rfm22b_dev->tx_data_wr = 0;
|
||||
PHPacketHandle p = NULL;
|
||||
|
||||
// Don't send if it's not our turn.
|
||||
if (!rfm22b_dev->time_to_send)
|
||||
return RFM22B_EVENT_RX_MODE;
|
||||
|
||||
// See if there's a packet ready to send.
|
||||
if (rfm22b_dev->tx_packet)
|
||||
p = rfm22b_dev->tx_packet;
|
||||
|
||||
// Are we waiting for an ACK?
|
||||
else
|
||||
{
|
||||
|
||||
// Don't send a packet if we're waiting for an ACK
|
||||
if (rfm22b_dev->prev_tx_packet)
|
||||
return RFM22B_EVENT_RX_MODE;
|
||||
|
||||
if (!p && rfm22b_dev->send_connection_request)
|
||||
{
|
||||
p = (PHPacketHandle)&(rfm22b_dev->con_packet);
|
||||
rfm22b_dev->send_connection_request = false;
|
||||
}
|
||||
|
||||
#ifdef PIOS_PPM_RECEIVER
|
||||
if (!p && rfm22b_dev->send_ppm)
|
||||
{
|
||||
p = (PHPacketHandle)&(rfm22b_dev->ppm_packet);
|
||||
rfm22b_dev->send_ppm = false;
|
||||
}
|
||||
#endif
|
||||
|
||||
if (!p && rfm22b_dev->send_status)
|
||||
{
|
||||
p = (PHPacketHandle)&(rfm22b_dev->status_packet);
|
||||
rfm22b_dev->send_status = false;
|
||||
}
|
||||
|
||||
if (!p)
|
||||
{
|
||||
// Try to get some data to send
|
||||
bool need_yield = false;
|
||||
p = &rfm22b_dev->data_packet;
|
||||
p->header.type = PACKET_TYPE_DATA;
|
||||
p->header.destination_id = rfm22b_dev->destination_id;
|
||||
if (rfm22b_dev->tx_out_cb && (p->header.data_size == 0))
|
||||
p->header.data_size = (rfm22b_dev->tx_out_cb)(rfm22b_dev->tx_out_context, p->data, PH_MAX_DATA, NULL, &need_yield);
|
||||
|
||||
// Don't send any data until we're connected.
|
||||
if (rfm22b_dev->stats.link_state != OPLINKSTATUS_LINKSTATE_CONNECTED)
|
||||
p->header.data_size = 0;
|
||||
if (p->header.data_size == 0)
|
||||
p = NULL;
|
||||
}
|
||||
|
||||
if (p)
|
||||
p->header.seq_num = rfm22b_dev->stats.tx_seq++;
|
||||
}
|
||||
if (!p)
|
||||
return RFM22B_EVENT_RX_MODE;
|
||||
|
||||
// We're transitioning out of Rx mode.
|
||||
rfm22b_dev->in_rx_mode = false;
|
||||
|
||||
#ifdef PIOS_RFM22B_DEBUG_ON_TELEM
|
||||
D1_LED_ON;
|
||||
D2_LED_OFF;
|
||||
D3_LED_TOGGLE;
|
||||
#endif
|
||||
|
||||
// Add the error correcting code.
|
||||
p->header.source_id = rfm22b_dev->deviceID;
|
||||
p->header.seq_num = rfm22b_dev->tx_packet_count++;
|
||||
encode_data((unsigned char*)p, PHPacketSize(p), (unsigned char*)p);
|
||||
|
||||
rfm22b_dev->tx_packet = p;
|
||||
@ -1363,11 +1414,11 @@ static enum pios_rfm22b_event rfm22_txStart(struct pios_rfm22b_dev *rfm22b_dev)
|
||||
rfm22b_dev->packet_start_ticks = 1;
|
||||
|
||||
// disable interrupts
|
||||
rfm22_write(RFM22_interrupt_enable1, 0x00);
|
||||
rfm22_write(RFM22_interrupt_enable2, 0x00);
|
||||
rfm22_write(rfm22b_dev, RFM22_interrupt_enable1, 0x00);
|
||||
rfm22_write(rfm22b_dev, RFM22_interrupt_enable2, 0x00);
|
||||
|
||||
// TUNE mode
|
||||
rfm22_write(RFM22_op_and_func_ctrl1, RFM22_opfc1_pllon);
|
||||
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);
|
||||
@ -1377,77 +1428,105 @@ static enum pios_rfm22b_event rfm22_txStart(struct pios_rfm22b_dev *rfm22b_dev)
|
||||
// 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(RFM22_transmit_header0, tx_buffer[0]);
|
||||
rfm22_write(RFM22_transmit_header1, tx_buffer[1]);
|
||||
rfm22_write(RFM22_transmit_header2, tx_buffer[2]);
|
||||
rfm22_write(RFM22_transmit_header3, tx_buffer[3]);
|
||||
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]);
|
||||
|
||||
// FIFO mode, GFSK modulation
|
||||
uint8_t fd_bit = rfm22_read(RFM22_modulation_mode_control2) & RFM22_mmc2_fd;
|
||||
rfm22_write(RFM22_modulation_mode_control2, fd_bit | RFM22_mmc2_dtmod_fifo |
|
||||
uint8_t fd_bit = rfm22_read(rfm22b_dev, RFM22_modulation_mode_control2) & RFM22_mmc2_fd;
|
||||
rfm22_write(rfm22b_dev, RFM22_modulation_mode_control2, fd_bit | RFM22_mmc2_dtmod_fifo |
|
||||
RFM22_mmc2_modtyp_gfsk);
|
||||
|
||||
// set the tx power
|
||||
rfm22_write(RFM22_tx_power, RFM22_tx_pwr_papeaken | RFM22_tx_pwr_papeaklvl_1 |
|
||||
RFM22_tx_pwr_papeaklvl_0 | RFM22_tx_pwr_lna_sw | g_rfm22b_dev->tx_power);
|
||||
rfm22_write(rfm22b_dev, RFM22_tx_power, RFM22_tx_pwr_papeaken | RFM22_tx_pwr_papeaklvl_1 |
|
||||
RFM22_tx_pwr_papeaklvl_0 | RFM22_tx_pwr_lna_sw | rfm22b_dev->tx_power);
|
||||
|
||||
// clear FIFOs
|
||||
rfm22_write(RFM22_op_and_func_ctrl2, RFM22_opfc2_ffclrrx | RFM22_opfc2_ffclrtx);
|
||||
rfm22_write(RFM22_op_and_func_ctrl2, 0x00);
|
||||
rfm22_write(rfm22b_dev, RFM22_op_and_func_ctrl2, RFM22_opfc2_ffclrrx | RFM22_opfc2_ffclrtx);
|
||||
rfm22_write(rfm22b_dev, RFM22_op_and_func_ctrl2, 0x00);
|
||||
|
||||
// *******************
|
||||
// add some data to the chips TX FIFO before enabling the transmitter
|
||||
|
||||
// set the total number of data bytes we are going to transmit
|
||||
rfm22_write(RFM22_transmit_packet_length, rfm22b_dev->tx_data_wr);
|
||||
rfm22_write(rfm22b_dev, RFM22_transmit_packet_length, rfm22b_dev->tx_data_wr);
|
||||
|
||||
// add some data
|
||||
rfm22_claimBus();
|
||||
rfm22_assertCs();
|
||||
PIOS_SPI_TransferByte(g_rfm22b_dev->spi_id, RFM22_fifo_access | 0x80);
|
||||
rfm22_claimBus(rfm22b_dev);
|
||||
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);
|
||||
bytes_to_write = (bytes_to_write > FIFO_SIZE) ? FIFO_SIZE: bytes_to_write;
|
||||
PIOS_SPI_TransferBlock(g_rfm22b_dev->spi_id, &tx_buffer[rfm22b_dev->tx_data_rd], NULL, bytes_to_write, NULL);
|
||||
PIOS_SPI_TransferBlock(rfm22b_dev->spi_id, &tx_buffer[rfm22b_dev->tx_data_rd], NULL, bytes_to_write, NULL);
|
||||
rfm22b_dev->tx_data_rd += bytes_to_write;
|
||||
rfm22_deassertCs();
|
||||
rfm22_releaseBus();
|
||||
rfm22_deassertCs(rfm22b_dev);
|
||||
rfm22_releaseBus(rfm22b_dev);
|
||||
|
||||
// enable TX interrupts
|
||||
rfm22_write(RFM22_interrupt_enable1, RFM22_ie1_enpksent | RFM22_ie1_entxffaem);
|
||||
rfm22_write(rfm22b_dev, RFM22_interrupt_enable1, RFM22_ie1_enpksent | RFM22_ie1_entxffaem);
|
||||
|
||||
// enable the transmitter
|
||||
rfm22_write(RFM22_op_and_func_ctrl1, RFM22_opfc1_pllon | RFM22_opfc1_txon);
|
||||
rfm22_write(rfm22b_dev, RFM22_op_and_func_ctrl1, RFM22_opfc1_pllon | RFM22_opfc1_txon);
|
||||
|
||||
TX_LED_ON;
|
||||
|
||||
return RFM22B_EVENT_TX_STARTED;
|
||||
return RFM22B_EVENT_NUM_EVENTS;
|
||||
}
|
||||
|
||||
static bool rfm22_sendStatus(struct pios_rfm22b_dev *rfm22b_dev)
|
||||
static void rfm22_sendStatus(struct pios_rfm22b_dev *rfm22b_dev)
|
||||
{
|
||||
PHPacketHandle sph = (PHPacketHandle)&(rfm22b_dev->status_packet);
|
||||
// Only send status if we're connected
|
||||
if (rfm22b_dev->stats.link_state != OPLINKSTATUS_LINKSTATE_CONNECTED)
|
||||
return;
|
||||
|
||||
// Update the link quality metric.
|
||||
rfm22_calculateLinkQuality(rfm22b_dev);
|
||||
|
||||
// Queue the status message
|
||||
rfm22b_dev->status_packet.header.destination_id = 0xffffffff; // Broadcast
|
||||
if (rfm22b_dev->stats.link_state == OPLINKSTATUS_LINKSTATE_CONNECTED)
|
||||
rfm22b_dev->status_packet.header.destination_id = rfm22b_dev->destination_id;
|
||||
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.errors = rfm22b_dev->errors;
|
||||
rfm22b_dev->status_packet.resets = rfm22b_dev->resets;
|
||||
rfm22b_dev->status_packet.retries = 0;
|
||||
rfm22b_dev->status_packet.uavtalk_errors = 0;
|
||||
rfm22b_dev->status_packet.dropped = 0;
|
||||
if (xQueueSend(rfm22b_dev->packetQueue, &sph, 0) != pdTRUE)
|
||||
return false;
|
||||
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;
|
||||
|
||||
// Process a SEND_PACKT event.
|
||||
enum pios_rfm22b_event event = RFM22B_EVENT_SEND_PACKET;
|
||||
while(event != RFM22B_EVENT_NUM_EVENTS)
|
||||
event = rfm22_process_state_transition(rfm22b_dev, event);
|
||||
|
||||
return true;
|
||||
return;
|
||||
}
|
||||
|
||||
// ************************************
|
||||
static void rfm22_sendPPM(struct pios_rfm22b_dev *rfm22b_dev)
|
||||
{
|
||||
#ifdef PIOS_PPM_RECEIVER
|
||||
// Only send PPM if we're connected
|
||||
if (rfm22b_dev->stats.link_state != OPLINKSTATUS_LINKSTATE_CONNECTED)
|
||||
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 = 1; i <= PIOS_PPM_NUM_INPUTS; ++i)
|
||||
{
|
||||
rfm22b_dev->ppm_packet.channels[i - 1] = PIOS_RCVR_Read(PIOS_PPM_RECEIVER, i);
|
||||
if(rfm22b_dev->ppm_packet.channels[i - 1] != 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
|
||||
}
|
||||
|
||||
/**
|
||||
* Read the RFM22B interrupt and device status registers
|
||||
@ -1457,23 +1536,23 @@ static bool rfm22_readStatus(struct pios_rfm22b_dev *rfm22b_dev)
|
||||
{
|
||||
|
||||
// 1. Read the interrupt statuses with burst read
|
||||
rfm22_claimBus(); // Set RC and the semaphore
|
||||
rfm22_claimBus(rfm22b_dev); // Set RC and the semaphore
|
||||
uint8_t write_buf[3] = {RFM22_interrupt_status1 & 0x7f, 0xFF, 0xFF};
|
||||
uint8_t read_buf[3];
|
||||
rfm22_assertCs();
|
||||
PIOS_SPI_TransferBlock(g_rfm22b_dev->spi_id, write_buf, read_buf, sizeof(write_buf), NULL);
|
||||
rfm22_deassertCs();
|
||||
rfm22_assertCs(rfm22b_dev);
|
||||
PIOS_SPI_TransferBlock(rfm22b_dev->spi_id, write_buf, read_buf, sizeof(write_buf), NULL);
|
||||
rfm22_deassertCs(rfm22b_dev);
|
||||
rfm22b_dev->int_status1 = read_buf[1];
|
||||
rfm22b_dev->int_status2 = read_buf[2];
|
||||
|
||||
// Device status
|
||||
rfm22b_dev->device_status = rfm22_read_noclaim(RFM22_device_status);
|
||||
rfm22b_dev->device_status = rfm22_read_noclaim(rfm22b_dev, RFM22_device_status);
|
||||
|
||||
// EzMAC status
|
||||
rfm22b_dev->ezmac_status = rfm22_read_noclaim(RFM22_ezmac_status);
|
||||
rfm22b_dev->ezmac_status = rfm22_read_noclaim(rfm22b_dev, RFM22_ezmac_status);
|
||||
|
||||
// Release the bus
|
||||
rfm22_releaseBus();
|
||||
rfm22_releaseBus(rfm22b_dev);
|
||||
|
||||
// the RF module has gone and done a reset - we need to re-initialize the rf module
|
||||
if (rfm22b_dev->int_status2 & RFM22_is2_ipor)
|
||||
@ -1482,12 +1561,26 @@ static bool rfm22_readStatus(struct pios_rfm22b_dev *rfm22b_dev)
|
||||
return true;
|
||||
}
|
||||
|
||||
/**
|
||||
* Add a status value to the RX packet status array.
|
||||
* \param[in] rfm22b_dev The device structure
|
||||
* \param[in] status The packet status value
|
||||
*/
|
||||
static void rfm22b_add_rx_status(struct pios_rfm22b_dev *rfm22b_dev, enum pios_rfm22b_rx_packet_status status)
|
||||
{
|
||||
// Shift the status registers
|
||||
for (uint8_t i = RFM22B_RX_PACKET_STATS_LEN - 1; i > 0; --i)
|
||||
{
|
||||
rfm22b_dev->rx_packet_stats[i] = (rfm22b_dev->rx_packet_stats[i] << 2) | (rfm22b_dev->rx_packet_stats[i - 1] >> 30);
|
||||
}
|
||||
rfm22b_dev->rx_packet_stats[0] = (rfm22b_dev->rx_packet_stats[0] << 2) | status;
|
||||
}
|
||||
|
||||
static enum pios_rfm22b_event rfm22_detectPreamble(struct pios_rfm22b_dev *rfm22b_dev)
|
||||
{
|
||||
|
||||
// Read the device status registers
|
||||
if (!rfm22_readStatus(rfm22b_dev))
|
||||
return RFM22B_EVENT_ERROR;
|
||||
return RFM22B_EVENT_FAILURE;
|
||||
|
||||
// Valid preamble detected
|
||||
if (rfm22b_dev->int_status2 & RFM22_is2_ipreaval)
|
||||
@ -1496,6 +1589,10 @@ static enum pios_rfm22b_event rfm22_detectPreamble(struct pios_rfm22b_dev *rfm22
|
||||
if (rfm22b_dev->packet_start_ticks == 0)
|
||||
rfm22b_dev->packet_start_ticks = 1;
|
||||
RX_LED_ON;
|
||||
|
||||
#ifdef PIOS_RFM22B_DEBUG_ON_TELEM
|
||||
D3_LED_TOGGLE;
|
||||
#endif
|
||||
return RFM22B_EVENT_PREAMBLE_DETECTED;
|
||||
}
|
||||
|
||||
@ -1507,7 +1604,7 @@ static enum pios_rfm22b_event rfm22_detectSync(struct pios_rfm22b_dev *rfm22b_de
|
||||
|
||||
// Read the device status registers
|
||||
if (!rfm22_readStatus(rfm22b_dev))
|
||||
return RFM22B_EVENT_ERROR;
|
||||
return RFM22B_EVENT_FAILURE;
|
||||
|
||||
// Sync word detected
|
||||
if (rfm22b_dev->int_status2 & RFM22_is2_iswdet)
|
||||
@ -1516,152 +1613,232 @@ static enum pios_rfm22b_event rfm22_detectSync(struct pios_rfm22b_dev *rfm22b_de
|
||||
|
||||
// read the 10-bit signed afc correction value
|
||||
// bits 9 to 2
|
||||
uint16_t afc_correction = (uint16_t)rfm22_read(RFM22_afc_correction_read) << 8;
|
||||
uint16_t afc_correction = (uint16_t)rfm22_read(rfm22b_dev, RFM22_afc_correction_read) << 8;
|
||||
// bits 1 & 0
|
||||
afc_correction |= (uint16_t)rfm22_read(RFM22_ook_counter_value1) & 0x00c0;
|
||||
afc_correction |= (uint16_t)rfm22_read(rfm22b_dev, RFM22_ook_counter_value1) & 0x00c0;
|
||||
afc_correction >>= 6;
|
||||
// convert the afc value to Hz
|
||||
rfm22b_dev->afc_correction_Hz = (int32_t)(rfm22b_dev->frequency_step_size * afc_correction + 0.5f);
|
||||
int32_t afc_corr = (int32_t)(rfm22b_dev->frequency_step_size * afc_correction + 0.5f);
|
||||
rfm22b_dev->afc_correction_Hz = (afc_corr < -127) ? -127 : ((afc_corr > 127) ? 127 : afc_corr);
|
||||
|
||||
// read rx signal strength .. 45 = -100dBm, 205 = -20dBm
|
||||
rfm22b_dev->rssi = rfm22_read(RFM22_rssi);
|
||||
uint8_t rssi = rfm22_read(rfm22b_dev, RFM22_rssi);
|
||||
// convert to dBm
|
||||
rfm22b_dev->rssi_dBm = (int8_t)(rfm22b_dev->rssi >> 1) - 122;
|
||||
|
||||
// remember the afc value for this packet
|
||||
rfm22b_dev->rx_packet_start_afc_Hz = rfm22b_dev->afc_correction_Hz;
|
||||
rfm22b_dev->rssi_dBm = (int8_t)(rssi >> 1) - 122;
|
||||
|
||||
return RFM22B_EVENT_SYNC_DETECTED;
|
||||
}
|
||||
else if (rfm22b_dev->int_status2 & !RFM22_is2_ipreaval)
|
||||
{
|
||||
// Waiting for sync timed out.
|
||||
return RFM22B_EVENT_TX_START;
|
||||
}
|
||||
return RFM22B_EVENT_FAILURE;
|
||||
|
||||
return RFM22B_EVENT_NUM_EVENTS;
|
||||
}
|
||||
|
||||
static bool rfm22_receivePacket(struct pios_rfm22b_dev *rfm22b_dev, PHPacketHandle p, uint16_t rx_len)
|
||||
{
|
||||
|
||||
// Attempt to correct any errors in the packet.
|
||||
decode_data((unsigned char*)p, rx_len);
|
||||
|
||||
bool good_packet = check_syndrome() == 0;
|
||||
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;
|
||||
|
||||
// Add any missed packets into the stats.
|
||||
bool ack_nack_packet = ((p->header.type == PACKET_TYPE_ACK) || (p->header.type == PACKET_TYPE_ACK_RTS) || (p->header.type == PACKET_TYPE_NACK));
|
||||
if (!ack_nack_packet && (good_packet || corrected_packet))
|
||||
{
|
||||
uint16_t seq_num = p->header.seq_num;
|
||||
if (rfm22b_dev->stats.link_state == OPLINKSTATUS_LINKSTATE_CONNECTED)
|
||||
{
|
||||
static bool first_time = true;
|
||||
uint16_t missed_packets = 0;
|
||||
if (first_time)
|
||||
first_time = false;
|
||||
else
|
||||
{
|
||||
uint16_t prev_seq_num = rfm22b_dev->stats.rx_seq;
|
||||
if (seq_num > prev_seq_num)
|
||||
missed_packets = seq_num - prev_seq_num - 1;
|
||||
else if((seq_num == prev_seq_num) && (p->header.type == PACKET_TYPE_DATA))
|
||||
p->header.type = PACKET_TYPE_DUPLICATE_DATA;
|
||||
}
|
||||
rfm22b_dev->stats.rx_missed += missed_packets;
|
||||
}
|
||||
rfm22b_dev->stats.rx_seq = seq_num;
|
||||
}
|
||||
|
||||
// Set the packet status
|
||||
if (good_packet)
|
||||
rfm22b_add_rx_status(rfm22b_dev, RFM22B_GOOD_RX_PACKET);
|
||||
else if(corrected_packet)
|
||||
// We corrected the error.
|
||||
rfm22b_add_rx_status(rfm22b_dev, RFM22B_CORRECTED_RX_PACKET);
|
||||
else
|
||||
// We couldn't correct the error, so drop the packet.
|
||||
rfm22b_add_rx_status(rfm22b_dev, RFM22B_ERROR_RX_PACKET);
|
||||
|
||||
return (good_packet || corrected_packet);
|
||||
}
|
||||
|
||||
static enum pios_rfm22b_event rfm22_rxData(struct pios_rfm22b_dev *rfm22b_dev)
|
||||
{
|
||||
// Swap in the next packet buffer if required.
|
||||
if (rfm22b_dev->rx_packet == NULL)
|
||||
{
|
||||
if (rfm22b_dev->rx_packet_next != NULL)
|
||||
rfm22b_dev->rx_packet = rfm22b_dev->rx_packet_next;
|
||||
else
|
||||
return RFM22B_EVENT_ERROR;
|
||||
}
|
||||
uint8_t *rx_buffer = (uint8_t*)(rfm22b_dev->rx_packet);
|
||||
uint8_t *rx_buffer = (uint8_t*)&(rfm22b_dev->rx_packet);
|
||||
|
||||
// Read the device status registers
|
||||
if (!rfm22_readStatus(rfm22b_dev))
|
||||
return RFM22B_EVENT_ERROR;
|
||||
return RFM22B_EVENT_FAILURE;
|
||||
|
||||
// FIFO under/over flow error. Restart RX mode.
|
||||
if (rfm22b_dev->device_status & (RFM22_ds_ffunfl | RFM22_ds_ffovfl))
|
||||
return RFM22B_EVENT_ERROR;
|
||||
if (rfm22b_dev->int_status1 & RFM22_is1_ifferr)
|
||||
return RFM22B_EVENT_FAILURE;
|
||||
|
||||
// RX FIFO almost full, it needs emptying
|
||||
if (rfm22b_dev->int_status1 & RFM22_is1_irxffafull)
|
||||
{
|
||||
// read data from the rf chips FIFO buffer
|
||||
// read the total length of the packet data
|
||||
uint16_t len = rfm22_read(RFM22_received_packet_length);
|
||||
uint16_t len = rfm22_read(rfm22b_dev, RFM22_received_packet_length);
|
||||
|
||||
// The received packet is going to be larger than the specified length
|
||||
if ((rfm22b_dev->rx_buffer_wr + RX_FIFO_HI_WATERMARK) > len)
|
||||
return RFM22B_EVENT_ERROR;
|
||||
return RFM22B_EVENT_FAILURE;
|
||||
|
||||
// Another packet length error.
|
||||
if (((rfm22b_dev->rx_buffer_wr + RX_FIFO_HI_WATERMARK) >= len) && !(rfm22b_dev->int_status1 & RFM22_is1_ipkvalid))
|
||||
return RFM22B_EVENT_ERROR;
|
||||
return RFM22B_EVENT_FAILURE;
|
||||
|
||||
// Fetch the data from the RX FIFO
|
||||
rfm22_claimBus();
|
||||
rfm22_assertCs();
|
||||
rfm22_claimBus(rfm22b_dev);
|
||||
rfm22_assertCs(rfm22b_dev);
|
||||
PIOS_SPI_TransferByte(rfm22b_dev->spi_id,RFM22_fifo_access & 0x7F);
|
||||
rfm22b_dev->rx_buffer_wr += (PIOS_SPI_TransferBlock(rfm22b_dev->spi_id ,OUT_FF, (uint8_t *)&rx_buffer[rfm22b_dev->rx_buffer_wr], RX_FIFO_HI_WATERMARK, NULL) == 0) ? RX_FIFO_HI_WATERMARK : 0;
|
||||
rfm22_deassertCs();
|
||||
rfm22_releaseBus();
|
||||
rfm22_deassertCs(rfm22b_dev);
|
||||
rfm22_releaseBus(rfm22b_dev);
|
||||
}
|
||||
|
||||
// CRC error .. discard the received data
|
||||
if (rfm22b_dev->int_status1 & RFM22_is1_icrerror)
|
||||
return RFM22B_EVENT_ERROR;
|
||||
return RFM22B_EVENT_FAILURE;
|
||||
|
||||
// Valid packet received
|
||||
if (rfm22b_dev->int_status1 & RFM22_is1_ipkvalid)
|
||||
{
|
||||
|
||||
// read the total length of the packet data
|
||||
uint32_t len = rfm22_read(RFM22_received_packet_length);
|
||||
uint32_t len = rfm22_read(rfm22b_dev, RFM22_received_packet_length);
|
||||
|
||||
// their 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
|
||||
rfm22_claimBus();
|
||||
rfm22_assertCs();
|
||||
rfm22_claimBus(rfm22b_dev);
|
||||
rfm22_assertCs(rfm22b_dev);
|
||||
PIOS_SPI_TransferByte(rfm22b_dev->spi_id,RFM22_fifo_access & 0x7F);
|
||||
rfm22b_dev->rx_buffer_wr += (PIOS_SPI_TransferBlock(rfm22b_dev->spi_id,OUT_FF, (uint8_t *)&rx_buffer[rfm22b_dev->rx_buffer_wr], bytes_to_read, NULL) == 0) ? bytes_to_read : 0;
|
||||
rfm22_deassertCs();
|
||||
rfm22_releaseBus();
|
||||
rfm22_deassertCs(rfm22b_dev);
|
||||
rfm22_releaseBus(rfm22b_dev);
|
||||
}
|
||||
|
||||
if (rfm22b_dev->rx_buffer_wr != len)
|
||||
return RFM22B_EVENT_ERROR;
|
||||
return RFM22B_EVENT_FAILURE;
|
||||
|
||||
// we have a valid received packet
|
||||
|
||||
enum pios_rfm22b_event ret_event = RFM22B_EVENT_RX_COMPLETE;
|
||||
if (rfm22b_dev->rx_buffer_wr > 0)
|
||||
{
|
||||
// Add the rssi and afc to the end of the packet.
|
||||
rx_buffer[rfm22b_dev->rx_buffer_wr++] = rfm22b_dev->rssi_dBm;
|
||||
rx_buffer[rfm22b_dev->rx_buffer_wr++] = rfm22b_dev->rx_packet_start_afc_Hz;
|
||||
// Swap the Rx packets.
|
||||
if (rfm22b_dev->rx_packet_prev == NULL)
|
||||
rfm22b_dev->stats.rx_byte_count += rfm22b_dev->rx_buffer_wr;
|
||||
// Check the packet for errors.
|
||||
if (rfm22_receivePacket(rfm22b_dev, &(rfm22b_dev->rx_packet), rfm22b_dev->rx_buffer_wr))
|
||||
{
|
||||
rfm22b_dev->rx_packet_prev = rfm22b_dev->rx_packet;
|
||||
rfm22b_dev->rx_packet = rfm22b_dev->rx_packet_next;
|
||||
rfm22b_dev->rx_packet_len = rfm22b_dev->rx_buffer_wr;
|
||||
// Signal the receive thread.
|
||||
xSemaphoreGive(rfm22b_dev->rxsem);
|
||||
switch (rfm22b_dev->rx_packet.header.type)
|
||||
{
|
||||
case PACKET_TYPE_STATUS:
|
||||
ret_event = RFM22B_EVENT_STATUS_RECEIVED;
|
||||
break;
|
||||
case PACKET_TYPE_CON_REQUEST:
|
||||
ret_event = RFM22B_EVENT_CONNECTION_REQUESTED;
|
||||
break;
|
||||
case PACKET_TYPE_DATA:
|
||||
{
|
||||
// Send the data to the com port
|
||||
bool rx_need_yield;
|
||||
if (rfm22b_dev->rx_in_cb)
|
||||
(rfm22b_dev->rx_in_cb)(rfm22b_dev->rx_in_context, rfm22b_dev->rx_packet.data, rfm22b_dev->rx_packet.header.data_size, NULL, &rx_need_yield);
|
||||
break;
|
||||
}
|
||||
case PACKET_TYPE_DUPLICATE_DATA:
|
||||
break;
|
||||
case PACKET_TYPE_ACK:
|
||||
case PACKET_TYPE_ACK_RTS:
|
||||
ret_event = RFM22B_EVENT_PACKET_ACKED;
|
||||
break;
|
||||
case PACKET_TYPE_NACK:
|
||||
ret_event = RFM22B_EVENT_PACKET_NACKED;
|
||||
break;
|
||||
case PACKET_TYPE_PPM:
|
||||
{
|
||||
PHPpmPacketHandle ppmp = (PHPpmPacketHandle)&(rfm22b_dev->rx_packet);
|
||||
for (uint8_t i = 0; i < PIOS_RFM22B_RCVR_MAX_CHANNELS; ++i)
|
||||
rfm22b_dev->ppm_channel[i] = ppmp->channels[i];
|
||||
rfm22b_dev->ppm_fresh = true;
|
||||
break;
|
||||
}
|
||||
default:
|
||||
break;
|
||||
}
|
||||
}
|
||||
else
|
||||
ret_event = RFM22B_EVENT_RX_ERROR;
|
||||
rfm22b_dev->rx_buffer_wr = 0;
|
||||
rfm22b_dev->rx_complete_ticks = xTaskGetTickCount();
|
||||
if (rfm22b_dev->rx_complete_ticks == 0)
|
||||
rfm22b_dev->rx_complete_ticks = 1;
|
||||
#ifdef PIOS_RFM22B_DEBUG_ON_TELEM
|
||||
D2_LED_OFF;
|
||||
D3_LED_TOGGLE;
|
||||
#endif
|
||||
}
|
||||
|
||||
// We're finished with Rx mode
|
||||
rfm22b_dev->in_rx_mode = false;
|
||||
|
||||
// Start a new transaction
|
||||
rfm22b_dev->packet_start_ticks = 0;
|
||||
return RFM22B_EVENT_RX_COMPLETE;
|
||||
return ret_event;
|
||||
}
|
||||
|
||||
return RFM22B_EVENT_NUM_EVENTS;
|
||||
}
|
||||
|
||||
static enum pios_rfm22b_event rfm22_rxFailure(struct pios_rfm22b_dev *rfm22b_dev)
|
||||
{
|
||||
rfm22b_dev->stats.rx_failure++;
|
||||
rfm22b_dev->rx_buffer_wr = 0;
|
||||
rfm22b_dev->rx_complete_ticks = xTaskGetTickCount();
|
||||
rfm22b_dev->in_rx_mode = false;
|
||||
if (rfm22b_dev->rx_complete_ticks == 0)
|
||||
rfm22b_dev->rx_complete_ticks = 1;
|
||||
return RFM22B_EVENT_RX_MODE;
|
||||
}
|
||||
|
||||
static enum pios_rfm22b_event rfm22_txData(struct pios_rfm22b_dev *rfm22b_dev)
|
||||
{
|
||||
enum pios_rfm22b_event ret_event = RFM22B_EVENT_NUM_EVENTS;
|
||||
|
||||
// Read the device status registers
|
||||
if (!rfm22_readStatus(rfm22b_dev))
|
||||
{
|
||||
// Free the tx packet
|
||||
PHReleaseTXPacket(pios_packet_handler, rfm22b_dev->tx_packet);
|
||||
rfm22b_dev->tx_packet = 0;
|
||||
rfm22b_dev->tx_data_wr = rfm22b_dev->tx_data_rd = 0;
|
||||
return RFM22B_EVENT_ERROR;
|
||||
}
|
||||
return RFM22B_EVENT_FAILURE;
|
||||
|
||||
// FIFO under/over flow error. Back to RX mode.
|
||||
if (rfm22b_dev->device_status & (RFM22_ds_ffunfl | RFM22_ds_ffovfl))
|
||||
{
|
||||
// Free the tx packet
|
||||
PHReleaseTXPacket(pios_packet_handler, rfm22b_dev->tx_packet);
|
||||
rfm22b_dev->tx_packet = 0;
|
||||
rfm22b_dev->tx_data_wr = rfm22b_dev->tx_data_rd = 0;
|
||||
return RFM22B_EVENT_ERROR;
|
||||
}
|
||||
// FIFO under/over flow error.
|
||||
//if (rfm22b_dev->int_status1 & RFM22_is1_ifferr)
|
||||
//return RFM22B_EVENT_FAILURE;
|
||||
|
||||
// TX FIFO almost empty, it needs filling up
|
||||
if (rfm22b_dev->int_status1 & RFM22_is1_ixtffaem)
|
||||
@ -1669,62 +1846,267 @@ static enum pios_rfm22b_event rfm22_txData(struct pios_rfm22b_dev *rfm22b_dev)
|
||||
// top-up the rf chips TX FIFO buffer
|
||||
uint8_t *tx_buffer = (uint8_t*)(rfm22b_dev->tx_packet);
|
||||
uint16_t max_bytes = FIFO_SIZE - TX_FIFO_LO_WATERMARK - 1;
|
||||
rfm22_claimBus();
|
||||
rfm22_assertCs();
|
||||
PIOS_SPI_TransferByte(g_rfm22b_dev->spi_id, RFM22_fifo_access | 0x80);
|
||||
rfm22_claimBus(rfm22b_dev);
|
||||
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);
|
||||
bytes_to_write = (bytes_to_write > max_bytes) ? max_bytes: bytes_to_write;
|
||||
PIOS_SPI_TransferBlock(g_rfm22b_dev->spi_id, &tx_buffer[rfm22b_dev->tx_data_rd], NULL, bytes_to_write, NULL);
|
||||
PIOS_SPI_TransferBlock(rfm22b_dev->spi_id, &tx_buffer[rfm22b_dev->tx_data_rd], NULL, bytes_to_write, NULL);
|
||||
rfm22b_dev->tx_data_rd += bytes_to_write;
|
||||
rfm22_deassertCs();
|
||||
rfm22_releaseBus();
|
||||
rfm22_deassertCs(rfm22b_dev);
|
||||
rfm22_releaseBus(rfm22b_dev);
|
||||
}
|
||||
|
||||
// Packet has been sent
|
||||
else if (rfm22b_dev->int_status1 & RFM22_is1_ipksent)
|
||||
{
|
||||
// Free the tx packet
|
||||
PHReleaseTXPacket(pios_packet_handler, rfm22b_dev->tx_packet);
|
||||
rfm22b_dev->stats.tx_byte_count += PH_PACKET_SIZE(rfm22b_dev->tx_packet);
|
||||
|
||||
// Is this an ACK?
|
||||
bool is_ack = ((rfm22b_dev->tx_packet->header.type == PACKET_TYPE_ACK) || (rfm22b_dev->tx_packet->header.type == PACKET_TYPE_ACK_RTS));
|
||||
//ret_event = is_ack ? RFM22B_EVENT_TX_START : RFM22B_EVENT_RX_MODE;
|
||||
ret_event = RFM22B_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 (rfm22b_dev->rx_packet.header.type == PACKET_TYPE_CON_REQUEST)
|
||||
rfm22_setConnectionParameters(rfm22b_dev);
|
||||
|
||||
}
|
||||
else if (rfm22b_dev->tx_packet->header.type != PACKET_TYPE_NACK)
|
||||
{
|
||||
// We need to wait for an ACK if this packet it not an ACK or NACK.
|
||||
rfm22b_dev->prev_tx_packet = rfm22b_dev->tx_packet;
|
||||
rfm22b_dev->tx_complete_ticks = xTaskGetTickCount();
|
||||
}
|
||||
// Set the Tx period
|
||||
portTickType curTicks = xTaskGetTickCount();
|
||||
if (rfm22b_dev->tx_packet->header.type == PACKET_TYPE_ACK)
|
||||
rfm22b_dev->time_to_send_offset = curTicks + 0x4;
|
||||
else if (rfm22b_dev->tx_packet->header.type == PACKET_TYPE_ACK_RTS)
|
||||
rfm22b_dev->time_to_send_offset = curTicks;
|
||||
rfm22b_dev->tx_packet = 0;
|
||||
rfm22b_dev->tx_data_wr = rfm22b_dev->tx_data_rd = 0;
|
||||
// Start a new transaction
|
||||
rfm22b_dev->packet_start_ticks = 0;
|
||||
return RFM22B_EVENT_TX_COMPLETE;
|
||||
|
||||
#ifdef PIOS_RFM22B_DEBUG_ON_TELEM
|
||||
D1_LED_OFF;
|
||||
D3_LED_TOGGLE;
|
||||
#endif
|
||||
}
|
||||
|
||||
return RFM22B_EVENT_NUM_EVENTS;
|
||||
return ret_event;
|
||||
}
|
||||
|
||||
// ************************************
|
||||
|
||||
// return the current mode
|
||||
int8_t rfm22_currentMode(void)
|
||||
static enum pios_rfm22b_event rfm22_txFailure(struct pios_rfm22b_dev *rfm22b_dev)
|
||||
{
|
||||
return g_rfm22b_dev->state;
|
||||
rfm22b_dev->stats.tx_failure++;
|
||||
rfm22b_dev->tx_data_wr = rfm22b_dev->tx_data_rd = 0;
|
||||
return RFM22B_EVENT_TX_START;
|
||||
}
|
||||
|
||||
// return true if we are transmitting
|
||||
bool rfm22_transmitting(void)
|
||||
/**
|
||||
* Send an ACK to a received packet.
|
||||
* \param[in] rfm22b_dev The device structure
|
||||
*/
|
||||
static enum pios_rfm22b_event rfm22_sendAck(struct pios_rfm22b_dev *rfm22b_dev)
|
||||
{
|
||||
return (g_rfm22b_dev->state == RFM22B_STATE_TX_DATA);
|
||||
PHAckNackPacketHandle aph = (PHAckNackPacketHandle)(&(rfm22b_dev->ack_nack_packet));
|
||||
aph->header.destination_id = rfm22b_dev->rx_packet.header.source_id;
|
||||
aph->header.type = rfm22_ready_to_send(rfm22b_dev) ? PACKET_TYPE_ACK_RTS : PACKET_TYPE_ACK;
|
||||
aph->header.data_size = PH_ACK_NACK_DATA_SIZE(aph);
|
||||
aph->header.seq_num = rfm22b_dev->rx_packet.header.seq_num;
|
||||
rfm22b_dev->tx_packet = (PHPacketHandle)aph;
|
||||
rfm22b_dev->time_to_send = true;
|
||||
return RFM22B_EVENT_TX_START;
|
||||
}
|
||||
|
||||
// return true if the channel is clear to transmit on
|
||||
bool rfm22_channelIsClear(void)
|
||||
/**
|
||||
* Send an NACK to a received packet.
|
||||
* \param[in] rfm22b_dev The device structure
|
||||
*/
|
||||
static enum pios_rfm22b_event rfm22_sendNack(struct pios_rfm22b_dev *rfm22b_dev)
|
||||
{
|
||||
if (g_rfm22b_dev->state != RFM22B_STATE_RX_MODE && g_rfm22b_dev->state != RFM22B_STATE_WAIT_PREAMBLE && g_rfm22b_dev->state != RFM22B_STATE_WAIT_SYNC)
|
||||
// we are receiving something or we are transmitting or we are scanning the spectrum
|
||||
return false;
|
||||
|
||||
return true;
|
||||
PHAckNackPacketHandle aph = (PHAckNackPacketHandle)(&(rfm22b_dev->ack_nack_packet));
|
||||
aph->header.destination_id = rfm22b_dev->rx_packet.header.source_id;
|
||||
aph->header.type = PACKET_TYPE_NACK;
|
||||
aph->header.data_size = PH_ACK_NACK_DATA_SIZE(aph);
|
||||
aph->header.seq_num = rfm22b_dev->rx_packet.header.seq_num;
|
||||
rfm22b_dev->tx_packet = (PHPacketHandle)aph;
|
||||
rfm22b_dev->time_to_send = true;
|
||||
return RFM22B_EVENT_TX_START;
|
||||
}
|
||||
|
||||
// ************************************
|
||||
// set/get the frequency calibration value
|
||||
|
||||
void rfm22_setFreqCalibration(uint8_t value)
|
||||
/**
|
||||
* Receive an ACK.
|
||||
* \param[in] rfm22b_dev The device structure
|
||||
*/
|
||||
static enum pios_rfm22b_event rfm22_receiveAck(struct pios_rfm22b_dev *rfm22b_dev)
|
||||
{
|
||||
rfm22_write(RFM22_xtal_osc_load_cap, value);
|
||||
PHPacketHandle prev = rfm22b_dev->prev_tx_packet;
|
||||
portTickType curTicks = xTaskGetTickCount();
|
||||
|
||||
// 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?
|
||||
if (rfm22b_dev->rx_packet.header.type == PACKET_TYPE_ACK)
|
||||
{
|
||||
rfm22b_dev->time_to_send_offset = curTicks;
|
||||
rfm22b_dev->time_to_send = true;
|
||||
return RFM22B_EVENT_TX_START;
|
||||
}
|
||||
else
|
||||
{
|
||||
rfm22b_dev->time_to_send_offset = curTicks + 0x4;
|
||||
return RFM22B_EVENT_RX_MODE;
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Receive an MACK.
|
||||
* \param[in] rfm22b_dev The device structure
|
||||
*/
|
||||
static enum pios_rfm22b_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;
|
||||
if (rfm22b_dev->stats.link_state == OPLINKSTATUS_LINKSTATE_CONNECTED)
|
||||
rfm22b_add_rx_status(rfm22b_dev, RFM22B_RESENT_TX_PACKET);
|
||||
rfm22b_dev->time_to_send = true;
|
||||
return RFM22B_EVENT_TX_START;
|
||||
}
|
||||
|
||||
/**
|
||||
* Receive a status packet
|
||||
* \param[in] rfm22b_dev The device structure
|
||||
*/
|
||||
static enum pios_rfm22b_event rfm22_receiveStatus(struct pios_rfm22b_dev *rfm22b_dev)
|
||||
{
|
||||
PHStatusPacketHandle status = (PHStatusPacketHandle)&(rfm22b_dev->rx_packet);
|
||||
int8_t rssi = rfm22b_dev->rssi_dBm;
|
||||
int8_t afc = rfm22b_dev->afc_correction_Hz;
|
||||
uint32_t id = status->header.source_id;
|
||||
bool found = false;
|
||||
// Have we seen this device recently?
|
||||
uint8_t id_idx = 0;
|
||||
for ( ; id_idx < OPLINKSTATUS_PAIRIDS_NUMELEM; ++id_idx)
|
||||
if(rfm22b_dev->pair_stats[id_idx].pairID == id)
|
||||
{
|
||||
found = true;
|
||||
break;
|
||||
}
|
||||
|
||||
// If we have seen it, update the RSSI and reset the last contact couter
|
||||
if(found)
|
||||
{
|
||||
rfm22b_dev->pair_stats[id_idx].rssi = rssi;
|
||||
rfm22b_dev->pair_stats[id_idx].afc_correction = afc;
|
||||
rfm22b_dev->pair_stats[id_idx].lastContact = 0;
|
||||
}
|
||||
|
||||
// If we haven't seen it, find a slot to put it in.
|
||||
if (!found)
|
||||
{
|
||||
uint8_t min_idx = 0;
|
||||
if(id != rfm22b_dev->destination_id)
|
||||
{
|
||||
int8_t min_rssi = rfm22b_dev->pair_stats[0].rssi;
|
||||
for (id_idx = 1; id_idx < OPLINKSTATUS_PAIRIDS_NUMELEM; ++id_idx)
|
||||
{
|
||||
if(rfm22b_dev->pair_stats[id_idx].rssi < min_rssi)
|
||||
{
|
||||
min_rssi = rfm22b_dev->pair_stats[id_idx].rssi;
|
||||
min_idx = id_idx;
|
||||
}
|
||||
}
|
||||
}
|
||||
rfm22b_dev->pair_stats[min_idx].pairID = id;
|
||||
rfm22b_dev->pair_stats[min_idx].rssi = rssi;
|
||||
rfm22b_dev->pair_stats[min_idx].afc_correction = afc;
|
||||
rfm22b_dev->pair_stats[min_idx].lastContact = 0;
|
||||
}
|
||||
|
||||
return RFM22B_EVENT_RX_COMPLETE;
|
||||
}
|
||||
|
||||
static enum pios_rfm22b_event rfm22_initConnection(struct pios_rfm22b_dev *rfm22b_dev)
|
||||
{
|
||||
if (rfm22b_dev->coordinator)
|
||||
return RFM22B_EVENT_REQUEST_CONNECTION;
|
||||
else
|
||||
return RFM22B_EVENT_WAIT_FOR_CONNECTION;
|
||||
}
|
||||
|
||||
static enum pios_rfm22b_event rfm22_requestConnection(struct pios_rfm22b_dev *rfm22b_dev)
|
||||
{
|
||||
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
|
||||
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->datarate = rfm22b_dev->datarate;
|
||||
cph->frequency_hz = rfm22b_dev->frequency_hz;
|
||||
cph->min_frequency = rfm22b_dev->min_frequency;
|
||||
cph->max_frequency = rfm22b_dev->max_frequency;
|
||||
cph->max_tx_power = rfm22b_dev->tx_power;
|
||||
rfm22b_dev->time_to_send = true;
|
||||
rfm22b_dev->send_connection_request = true;
|
||||
|
||||
return RFM22B_EVENT_TX_START;
|
||||
}
|
||||
|
||||
static void rfm22_setConnectionParameters(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;
|
||||
|
||||
// Configure this modem from the connection request message.
|
||||
rfm22_setDatarate(rfm22b_dev, cph->datarate, true);
|
||||
PIOS_RFM22B_SetTxPower((uint32_t)rfm22b_dev, cph->max_tx_power);
|
||||
rfm22b_dev->min_frequency = cph->min_frequency;
|
||||
rfm22b_dev->max_frequency = cph->max_frequency;
|
||||
rfm22_setNominalCarrierFrequency(rfm22b_dev, cph->frequency_hz);
|
||||
|
||||
// Call the com port configuration function
|
||||
if (rfm22b_dev->com_config_cb && !rfm22b_dev->coordinator)
|
||||
rfm22b_dev->com_config_cb(cph->port, cph->com_speed);
|
||||
}
|
||||
|
||||
static enum pios_rfm22b_event rfm22_acceptConnection(struct pios_rfm22b_dev *rfm22b_dev)
|
||||
{
|
||||
// Set our connection state to connected
|
||||
rfm22b_dev->stats.link_state = OPLINKSTATUS_LINKSTATE_CONNECTED;
|
||||
|
||||
// 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.
|
||||
PIOS_RFM22B_SetDestinationId((uint32_t)rfm22b_dev, cph->header.source_id);
|
||||
|
||||
return RFM22B_EVENT_CONNECTION_ACCEPTED;
|
||||
}
|
||||
|
||||
// ************************************
|
||||
@ -1732,13 +2114,49 @@ void rfm22_setFreqCalibration(uint8_t value)
|
||||
|
||||
static enum pios_rfm22b_event rfm22_init(struct pios_rfm22b_dev *rfm22b_dev)
|
||||
{
|
||||
uint32_t id = rfm22b_dev->deviceID;
|
||||
uint32_t min_frequency_hz = rfm22b_dev->cfg.minFrequencyHz;
|
||||
uint32_t max_frequency_hz = rfm22b_dev->cfg.maxFrequencyHz;
|
||||
uint32_t freq_hop_step_size = 50000;
|
||||
|
||||
// Initialize the register values.
|
||||
rfm22b_dev->device_status = 0;
|
||||
rfm22b_dev->int_status1 = 0;
|
||||
rfm22b_dev->int_status2 = 0;
|
||||
rfm22b_dev->ezmac_status = 0;
|
||||
|
||||
// Clean the LEDs
|
||||
rfm22_clearLEDs();
|
||||
|
||||
// Initialize the detected device statistics.
|
||||
for (uint8_t i = 0; i < OPLINKSTATUS_PAIRIDS_NUMELEM; ++i)
|
||||
{
|
||||
rfm22b_dev->pair_stats[i].pairID = 0;
|
||||
rfm22b_dev->pair_stats[i].rssi = -127;
|
||||
rfm22b_dev->pair_stats[i].afc_correction = 0;
|
||||
rfm22b_dev->pair_stats[i].lastContact = 0;
|
||||
}
|
||||
|
||||
// Initlize the link stats.
|
||||
for (uint8_t i = 0; i < RFM22B_RX_PACKET_STATS_LEN; ++i)
|
||||
rfm22b_dev->rx_packet_stats[i] = 0;
|
||||
|
||||
// Initialize the state
|
||||
rfm22b_dev->stats.link_state = OPLINKSTATUS_LINKSTATE_DISCONNECTED;
|
||||
rfm22b_dev->tx_power = RFM22B_DEFAULT_TX_POWER;
|
||||
rfm22b_dev->destination_id = 0xffffffff;
|
||||
rfm22b_dev->time_to_send = false;
|
||||
rfm22b_dev->time_to_send_offset = 0;
|
||||
rfm22b_dev->send_status = false;
|
||||
rfm22b_dev->send_connection_request = false;
|
||||
|
||||
// Initialize the packets.
|
||||
rfm22b_dev->rx_packet_len = 0;
|
||||
rfm22b_dev->tx_packet = NULL;
|
||||
rfm22b_dev->prev_tx_packet = NULL;
|
||||
rfm22b_dev->stats.tx_seq = 0;
|
||||
rfm22b_dev->stats.rx_seq = 0;
|
||||
rfm22b_dev->data_packet.header.data_size = 0;
|
||||
rfm22b_dev->in_rx_mode = false;
|
||||
|
||||
// software reset the RF chip .. following procedure according to Si4x3x Errata (rev. B)
|
||||
rfm22_write(RFM22_op_and_func_ctrl1, RFM22_opfc1_swres);
|
||||
rfm22_write(rfm22b_dev, RFM22_op_and_func_ctrl1, RFM22_opfc1_swres);
|
||||
|
||||
// wait 26ms
|
||||
PIOS_DELAY_WaitmS(26);
|
||||
@ -1749,22 +2167,22 @@ static enum pios_rfm22b_event rfm22_init(struct pios_rfm22b_dev *rfm22b_dev)
|
||||
PIOS_DELAY_WaitmS(1);
|
||||
|
||||
// read the status registers
|
||||
rfm22b_dev->int_status1 = rfm22_read(RFM22_interrupt_status1);
|
||||
rfm22b_dev->int_status2 = rfm22_read(RFM22_interrupt_status2);
|
||||
rfm22b_dev->int_status1 = rfm22_read(rfm22b_dev, RFM22_interrupt_status1);
|
||||
rfm22b_dev->int_status2 = rfm22_read(rfm22b_dev, RFM22_interrupt_status2);
|
||||
if (rfm22b_dev->int_status2 & RFM22_is2_ichiprdy) break;
|
||||
}
|
||||
|
||||
// ****************
|
||||
|
||||
// read status - clears interrupt
|
||||
rfm22b_dev->device_status = rfm22_read(RFM22_device_status);
|
||||
rfm22b_dev->int_status1 = rfm22_read(RFM22_interrupt_status1);
|
||||
rfm22b_dev->int_status2 = rfm22_read(RFM22_interrupt_status2);
|
||||
rfm22b_dev->ezmac_status = rfm22_read(RFM22_ezmac_status);
|
||||
rfm22b_dev->device_status = rfm22_read(rfm22b_dev, RFM22_device_status);
|
||||
rfm22b_dev->int_status1 = rfm22_read(rfm22b_dev, RFM22_interrupt_status1);
|
||||
rfm22b_dev->int_status2 = rfm22_read(rfm22b_dev, RFM22_interrupt_status2);
|
||||
rfm22b_dev->ezmac_status = rfm22_read(rfm22b_dev, RFM22_ezmac_status);
|
||||
|
||||
// disable all interrupts
|
||||
rfm22_write(RFM22_interrupt_enable1, 0x00);
|
||||
rfm22_write(RFM22_interrupt_enable2, 0x00);
|
||||
rfm22_write(rfm22b_dev, RFM22_interrupt_enable1, 0x00);
|
||||
rfm22_write(rfm22b_dev, RFM22_interrupt_enable2, 0x00);
|
||||
|
||||
// ****************
|
||||
|
||||
@ -1779,14 +2197,16 @@ static enum pios_rfm22b_event rfm22_init(struct pios_rfm22b_dev *rfm22b_dev)
|
||||
rfm22b_dev->afc_correction_Hz = 0;
|
||||
|
||||
rfm22b_dev->packet_start_ticks = 0;
|
||||
rfm22b_dev->tx_complete_ticks = 0;
|
||||
rfm22b_dev->rx_complete_ticks = 0;
|
||||
|
||||
// ****************
|
||||
// read the RF chip ID bytes
|
||||
|
||||
// read the device type
|
||||
uint8_t device_type = rfm22_read(RFM22_DEVICE_TYPE) & RFM22_DT_MASK;
|
||||
uint8_t device_type = rfm22_read(rfm22b_dev, RFM22_DEVICE_TYPE) & RFM22_DT_MASK;
|
||||
// read the device version
|
||||
uint8_t device_version = rfm22_read(RFM22_DEVICE_VERSION) & RFM22_DV_MASK;
|
||||
uint8_t device_version = rfm22_read(rfm22b_dev, RFM22_DEVICE_VERSION) & RFM22_DV_MASK;
|
||||
|
||||
#if defined(RFM22_DEBUG)
|
||||
DEBUG_PRINTF(2, "rf device type: %d\n\r", device_type);
|
||||
@ -1812,99 +2232,88 @@ static enum pios_rfm22b_event rfm22_init(struct pios_rfm22b_dev *rfm22b_dev)
|
||||
|
||||
// ****************
|
||||
// set the minimum and maximum carrier frequency allowed
|
||||
|
||||
if (min_frequency_hz < RFM22_MIN_CARRIER_FREQUENCY_HZ) min_frequency_hz = RFM22_MIN_CARRIER_FREQUENCY_HZ;
|
||||
else
|
||||
if (min_frequency_hz > RFM22_MAX_CARRIER_FREQUENCY_HZ) min_frequency_hz = RFM22_MAX_CARRIER_FREQUENCY_HZ;
|
||||
|
||||
if (max_frequency_hz < RFM22_MIN_CARRIER_FREQUENCY_HZ) max_frequency_hz = RFM22_MIN_CARRIER_FREQUENCY_HZ;
|
||||
else
|
||||
if (max_frequency_hz > RFM22_MAX_CARRIER_FREQUENCY_HZ) max_frequency_hz = RFM22_MAX_CARRIER_FREQUENCY_HZ;
|
||||
|
||||
if (min_frequency_hz > max_frequency_hz)
|
||||
{ // swap them over
|
||||
uint32_t tmp = min_frequency_hz;
|
||||
min_frequency_hz = max_frequency_hz;
|
||||
max_frequency_hz = tmp;
|
||||
}
|
||||
rfm22b_dev->min_frequency = RFM22B_DEFAULT_MIN_FREQUENCY;
|
||||
rfm22b_dev->max_frequency = RFM22B_DEFAULT_MAX_FREQUENCY;
|
||||
rfm22b_dev->frequency_hz = RFM22B_DEFAULT_FREQUENCY;
|
||||
|
||||
// ****************
|
||||
// calibrate our RF module to be exactly on frequency .. different for every module
|
||||
rfm22_write(RFM22_xtal_osc_load_cap, OSC_LOAD_CAP);
|
||||
rfm22_write(rfm22b_dev, RFM22_xtal_osc_load_cap, OSC_LOAD_CAP);
|
||||
|
||||
// ****************
|
||||
|
||||
// disable Low Duty Cycle Mode
|
||||
rfm22_write(RFM22_op_and_func_ctrl2, 0x00);
|
||||
rfm22_write(rfm22b_dev, RFM22_op_and_func_ctrl2, 0x00);
|
||||
|
||||
// 1MHz clock output
|
||||
rfm22_write(RFM22_cpu_output_clk, RFM22_coc_1MHz);
|
||||
rfm22_write(rfm22b_dev, RFM22_cpu_output_clk, RFM22_coc_1MHz);
|
||||
|
||||
// READY mode
|
||||
rfm22_write(RFM22_op_and_func_ctrl1, RFM22_opfc1_xton);
|
||||
rfm22_write(rfm22b_dev, RFM22_op_and_func_ctrl1, RFM22_opfc1_xton);
|
||||
|
||||
// choose the 3 GPIO pin functions
|
||||
// GPIO port use default value
|
||||
rfm22_write(RFM22_io_port_config, RFM22_io_port_default);
|
||||
rfm22_write(rfm22b_dev, RFM22_io_port_config, RFM22_io_port_default);
|
||||
if (rfm22b_dev->cfg.gpio_direction == GPIO0_TX_GPIO1_RX) {
|
||||
rfm22_write(RFM22_gpio0_config, RFM22_gpio0_config_drv3 | RFM22_gpio0_config_txstate); // GPIO0 = TX State (to control RF Switch)
|
||||
rfm22_write(RFM22_gpio1_config, RFM22_gpio1_config_drv3 | RFM22_gpio1_config_rxstate); // GPIO1 = RX State (to control RF Switch)
|
||||
rfm22_write(rfm22b_dev, RFM22_gpio0_config, RFM22_gpio0_config_drv3 | RFM22_gpio0_config_txstate); // GPIO0 = TX State (to control RF Switch)
|
||||
rfm22_write(rfm22b_dev, RFM22_gpio1_config, RFM22_gpio1_config_drv3 | RFM22_gpio1_config_rxstate); // GPIO1 = RX State (to control RF Switch)
|
||||
} else {
|
||||
rfm22_write(RFM22_gpio0_config, RFM22_gpio0_config_drv3 | RFM22_gpio0_config_rxstate); // GPIO0 = TX State (to control RF Switch)
|
||||
rfm22_write(RFM22_gpio1_config, RFM22_gpio1_config_drv3 | RFM22_gpio1_config_txstate); // GPIO1 = RX State (to control RF Switch)
|
||||
rfm22_write(rfm22b_dev, RFM22_gpio0_config, RFM22_gpio0_config_drv3 | RFM22_gpio0_config_rxstate); // GPIO0 = TX State (to control RF Switch)
|
||||
rfm22_write(rfm22b_dev, RFM22_gpio1_config, RFM22_gpio1_config_drv3 | RFM22_gpio1_config_txstate); // GPIO1 = RX State (to control RF Switch)
|
||||
}
|
||||
rfm22_write(RFM22_gpio2_config, RFM22_gpio2_config_drv3 | RFM22_gpio2_config_cca); // GPIO2 = Clear Channel Assessment
|
||||
rfm22_write(rfm22b_dev, RFM22_gpio2_config, RFM22_gpio2_config_drv3 | RFM22_gpio2_config_cca); // GPIO2 = Clear Channel Assessment
|
||||
|
||||
// ****************
|
||||
|
||||
// initialize the frequency hopping step size
|
||||
uint32_t freq_hop_step_size = 50000;
|
||||
freq_hop_step_size /= 10000; // in 10kHz increments
|
||||
if (freq_hop_step_size > 255) freq_hop_step_size = 255;
|
||||
rfm22b_dev->frequency_hop_step_size_reg = freq_hop_step_size;
|
||||
|
||||
// FIFO mode, GFSK modulation
|
||||
uint8_t fd_bit = rfm22_read(RFM22_modulation_mode_control2) & RFM22_mmc2_fd;
|
||||
rfm22_write(RFM22_modulation_mode_control2, RFM22_mmc2_trclk_clk_none | RFM22_mmc2_dtmod_fifo | fd_bit | RFM22_mmc2_modtyp_gfsk);
|
||||
uint8_t fd_bit = rfm22_read(rfm22b_dev, RFM22_modulation_mode_control2) & RFM22_mmc2_fd;
|
||||
rfm22_write(rfm22b_dev, RFM22_modulation_mode_control2, RFM22_mmc2_trclk_clk_none | RFM22_mmc2_dtmod_fifo | fd_bit | RFM22_mmc2_modtyp_gfsk);
|
||||
|
||||
// setup to read the internal temperature sensor
|
||||
|
||||
// ADC used to sample the temperature sensor
|
||||
uint8_t adc_config = RFM22_ac_adcsel_temp_sensor | RFM22_ac_adcref_bg;
|
||||
rfm22_write(RFM22_adc_config, adc_config);
|
||||
rfm22_write(rfm22b_dev, RFM22_adc_config, adc_config);
|
||||
|
||||
// adc offset
|
||||
rfm22_write(RFM22_adc_sensor_amp_offset, 0);
|
||||
rfm22_write(rfm22b_dev, RFM22_adc_sensor_amp_offset, 0);
|
||||
|
||||
// temp sensor calibration .. <20>40C to +64C 0.5C resolution
|
||||
rfm22_write(RFM22_temp_sensor_calib, RFM22_tsc_tsrange0 | RFM22_tsc_entsoffs);
|
||||
rfm22_write(rfm22b_dev, RFM22_temp_sensor_calib, RFM22_tsc_tsrange0 | RFM22_tsc_entsoffs);
|
||||
|
||||
// temp sensor offset
|
||||
rfm22_write(RFM22_temp_value_offset, 0);
|
||||
rfm22_write(rfm22b_dev, RFM22_temp_value_offset, 0);
|
||||
|
||||
// start an ADC conversion
|
||||
rfm22_write(RFM22_adc_config, adc_config | RFM22_ac_adcstartbusy);
|
||||
rfm22_write(rfm22b_dev, RFM22_adc_config, adc_config | RFM22_ac_adcstartbusy);
|
||||
|
||||
// set the RSSI threshold interrupt to about -90dBm
|
||||
rfm22_write(RFM22_rssi_threshold_clear_chan_indicator, (-90 + 122) * 2);
|
||||
rfm22_write(rfm22b_dev, RFM22_rssi_threshold_clear_chan_indicator, (-90 + 122) * 2);
|
||||
|
||||
// enable the internal Tx & Rx packet handlers (without CRC)
|
||||
rfm22_write(RFM22_data_access_control, RFM22_dac_enpacrx | RFM22_dac_enpactx);
|
||||
rfm22_write(rfm22b_dev, RFM22_data_access_control, RFM22_dac_enpacrx | RFM22_dac_enpactx);
|
||||
|
||||
// x-nibbles tx preamble
|
||||
rfm22_write(RFM22_preamble_length, TX_PREAMBLE_NIBBLES);
|
||||
rfm22_write(rfm22b_dev, RFM22_preamble_length, TX_PREAMBLE_NIBBLES);
|
||||
// x-nibbles rx preamble detection
|
||||
rfm22_write(RFM22_preamble_detection_ctrl1, RX_PREAMBLE_NIBBLES << 3);
|
||||
rfm22_write(rfm22b_dev, RFM22_preamble_detection_ctrl1, RX_PREAMBLE_NIBBLES << 3);
|
||||
|
||||
#ifdef PIOS_RFM22_NO_HEADER
|
||||
// header control - we are not using the header
|
||||
rfm22_write(RFM22_header_control1, RFM22_header_cntl1_bcen_none | RFM22_header_cntl1_hdch_none);
|
||||
rfm22_write(rfm22b_dev, RFM22_header_control1, RFM22_header_cntl1_bcen_none | RFM22_header_cntl1_hdch_none);
|
||||
|
||||
// no header bytes, synchronization word length 3, 2, 1 & 0 used, packet length included in header.
|
||||
rfm22_write(RFM22_header_control2, RFM22_header_cntl2_hdlen_none |
|
||||
rfm22_write(rfm22b_dev, RFM22_header_control2, RFM22_header_cntl2_hdlen_none |
|
||||
RFM22_header_cntl2_synclen_3210 | ((TX_PREAMBLE_NIBBLES >> 8) & 0x01));
|
||||
#else
|
||||
// header control - using a 4 by header with broadcast of 0xffffffff
|
||||
rfm22_write(RFM22_header_control1,
|
||||
rfm22_write(rfm22b_dev, RFM22_header_control1,
|
||||
RFM22_header_cntl1_bcen_0 |
|
||||
RFM22_header_cntl1_bcen_1 |
|
||||
RFM22_header_cntl1_bcen_2 |
|
||||
@ -1914,66 +2323,93 @@ static enum pios_rfm22b_event rfm22_init(struct pios_rfm22b_dev *rfm22b_dev)
|
||||
RFM22_header_cntl1_hdch_2 |
|
||||
RFM22_header_cntl1_hdch_3);
|
||||
// Check all bit of all bytes of the header
|
||||
rfm22_write(RFM22_header_enable0, 0xff);
|
||||
rfm22_write(RFM22_header_enable1, 0xff);
|
||||
rfm22_write(RFM22_header_enable2, 0xff);
|
||||
rfm22_write(RFM22_header_enable3, 0xff);
|
||||
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
|
||||
rfm22_write(RFM22_check_header0, id & 0xff);
|
||||
rfm22_write(RFM22_check_header1, (id >> 8) & 0xff);
|
||||
rfm22_write(RFM22_check_header2, (id >> 16) & 0xff);
|
||||
rfm22_write(RFM22_check_header3, (id >> 24) & 0xff);
|
||||
uint32_t id = rfm22b_dev->deviceID;
|
||||
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);
|
||||
rfm22_write(rfm22b_dev, RFM22_check_header3, (id >> 24) & 0xff);
|
||||
// 4 header bytes, synchronization word length 3, 2, 1 & 0 used, packet length included in header.
|
||||
rfm22_write(RFM22_header_control2,
|
||||
rfm22_write(rfm22b_dev, RFM22_header_control2,
|
||||
RFM22_header_cntl2_hdlen_3210 |
|
||||
RFM22_header_cntl2_synclen_3210 |
|
||||
((TX_PREAMBLE_NIBBLES >> 8) & 0x01));
|
||||
#endif
|
||||
|
||||
// sync word
|
||||
rfm22_write(RFM22_sync_word3, SYNC_BYTE_1);
|
||||
rfm22_write(RFM22_sync_word2, SYNC_BYTE_2);
|
||||
rfm22_write(RFM22_sync_word1, SYNC_BYTE_3);
|
||||
rfm22_write(RFM22_sync_word0, SYNC_BYTE_4);
|
||||
rfm22_write(rfm22b_dev, RFM22_sync_word3, SYNC_BYTE_1);
|
||||
rfm22_write(rfm22b_dev, RFM22_sync_word2, SYNC_BYTE_2);
|
||||
rfm22_write(rfm22b_dev, RFM22_sync_word1, SYNC_BYTE_3);
|
||||
rfm22_write(rfm22b_dev, RFM22_sync_word0, SYNC_BYTE_4);
|
||||
|
||||
rfm22_write(RFM22_agc_override1, RFM22_agc_ovr1_agcen);
|
||||
rfm22_write(rfm22b_dev, RFM22_agc_override1, RFM22_agc_ovr1_agcen);
|
||||
|
||||
// set frequency hopping channel step size (multiples of 10kHz)
|
||||
rfm22_write(RFM22_frequency_hopping_step_size, rfm22b_dev->frequency_hop_step_size_reg);
|
||||
|
||||
// set our nominal carrier frequency
|
||||
rfm22_setNominalCarrierFrequency(rfm22b_dev, (min_frequency_hz + max_frequency_hz) / 2);
|
||||
rfm22_write(rfm22b_dev, RFM22_frequency_hopping_step_size, rfm22b_dev->frequency_hop_step_size_reg);
|
||||
|
||||
// set the tx power
|
||||
rfm22_write(RFM22_tx_power, RFM22_tx_pwr_papeaken | RFM22_tx_pwr_papeaklvl_0 | RFM22_tx_pwr_lna_sw | rfm22b_dev->tx_power);
|
||||
rfm22_write(rfm22b_dev, RFM22_tx_power, RFM22_tx_pwr_papeaken | RFM22_tx_pwr_papeaklvl_0 | RFM22_tx_pwr_lna_sw | rfm22b_dev->tx_power);
|
||||
|
||||
// TX FIFO Almost Full Threshold (0 - 63)
|
||||
rfm22_write(RFM22_tx_fifo_control1, TX_FIFO_HI_WATERMARK);
|
||||
rfm22_write(rfm22b_dev, RFM22_tx_fifo_control1, TX_FIFO_HI_WATERMARK);
|
||||
|
||||
// TX FIFO Almost Empty Threshold (0 - 63)
|
||||
rfm22_write(RFM22_tx_fifo_control2, TX_FIFO_LO_WATERMARK);
|
||||
rfm22_write(rfm22b_dev, RFM22_tx_fifo_control2, TX_FIFO_LO_WATERMARK);
|
||||
|
||||
// RX FIFO Almost Full Threshold (0 - 63)
|
||||
rfm22_write(RFM22_rx_fifo_control, RX_FIFO_HI_WATERMARK);
|
||||
rfm22_write(rfm22b_dev, RFM22_rx_fifo_control, RX_FIFO_HI_WATERMARK);
|
||||
|
||||
rfm22_setFreqCalibration(rfm22b_dev->cfg.RFXtalCap);
|
||||
rfm22_setNominalCarrierFrequency(rfm22b_dev, rfm22b_dev->cfg.frequencyHz);
|
||||
RFM22_SetDatarate((uint32_t)rfm22b_dev, rfm22b_dev->datarate, true);
|
||||
// Set the frequency calibration
|
||||
rfm22_write(rfm22b_dev, RFM22_xtal_osc_load_cap, rfm22b_dev->cfg.RFXtalCap);
|
||||
|
||||
// Initialize the frequency and datarate to te default.
|
||||
rfm22_setNominalCarrierFrequency(rfm22b_dev, RFM22B_DEFAULT_FREQUENCY);
|
||||
rfm22_setDatarate(rfm22b_dev, RFM22B_DEFAULT_RX_DATARATE, true);
|
||||
|
||||
return RFM22B_EVENT_INITIALIZED;
|
||||
}
|
||||
|
||||
static void rfm22_clearLEDs() {
|
||||
LINK_LED_OFF;
|
||||
RX_LED_OFF;
|
||||
TX_LED_OFF;
|
||||
#ifdef PIOS_RFM22B_DEBUG_ON_TELEM
|
||||
D1_LED_OFF;
|
||||
D2_LED_OFF;
|
||||
D3_LED_OFF;
|
||||
D4_LED_OFF;
|
||||
#endif
|
||||
}
|
||||
|
||||
static enum pios_rfm22b_event rfm22_timeout(struct pios_rfm22b_dev *rfm22b_dev)
|
||||
{
|
||||
rfm22b_dev->resets++;
|
||||
rfm22b_dev->stats.timeouts++;
|
||||
rfm22b_dev->packet_start_ticks = 0;
|
||||
// Release the Tx packet if it's set.
|
||||
if (rfm22b_dev->tx_packet != 0)
|
||||
{
|
||||
rfm22b_dev->tx_data_rd = rfm22b_dev->tx_data_wr = 0;
|
||||
}
|
||||
rfm22b_dev->rx_buffer_wr = 0;
|
||||
TX_LED_OFF;
|
||||
RX_LED_OFF;
|
||||
#ifdef PIOS_RFM22B_DEBUG_ON_TELEM
|
||||
D1_LED_OFF;
|
||||
D2_LED_OFF;
|
||||
D3_LED_OFF;
|
||||
D4_LED_OFF;
|
||||
#endif
|
||||
return RFM22B_EVENT_TX_START;
|
||||
}
|
||||
|
||||
static enum pios_rfm22b_event rfm22_error(struct pios_rfm22b_dev *rfm22b_dev)
|
||||
{
|
||||
rfm22b_dev->resets++;
|
||||
rfm22b_dev->packet_start_ticks = 0;
|
||||
rfm22b_dev->stats.resets++;
|
||||
rfm22_clearLEDs();
|
||||
return RFM22B_EVENT_INITIALIZE;
|
||||
}
|
||||
|
||||
@ -1985,8 +2421,8 @@ static enum pios_rfm22b_event rfm22_error(struct pios_rfm22b_dev *rfm22b_dev)
|
||||
*/
|
||||
static enum pios_rfm22b_event rfm22_fatal_error(struct pios_rfm22b_dev *rfm22b_dev)
|
||||
{
|
||||
|
||||
// RF module error .. flash the LED's
|
||||
rfm22_clearLEDs();
|
||||
for(unsigned int j = 0; j < 16; j++)
|
||||
{
|
||||
USB_LED_ON;
|
||||
|
130
flight/PiOS/Common/pios_rfm22b_com.c
Normal file
130
flight/PiOS/Common/pios_rfm22b_com.c
Normal file
@ -0,0 +1,130 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup PIOS PIOS Core hardware abstraction layer
|
||||
* @{
|
||||
* @addtogroup PIOS_RFM22B Radio Functions
|
||||
* @brief PIOS COM interface for for the RFM22B radio
|
||||
* @{
|
||||
*
|
||||
* @file pios_rfm22b_com.c
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @brief Implements a driver the the RFM22B driver
|
||||
* @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
|
||||
*/
|
||||
|
||||
/* Project Includes */
|
||||
#include <pios.h>
|
||||
|
||||
#include <pios_rfm22b_priv.h>
|
||||
|
||||
/* Provide a COM driver */
|
||||
static void PIOS_RFM22B_COM_ChangeBaud(uint32_t rfm22b_id, uint32_t baud);
|
||||
static void PIOS_RFM22B_COM_RegisterRxCallback(uint32_t rfm22b_id, pios_com_callback rx_in_cb, uint32_t context);
|
||||
static void PIOS_RFM22B_COM_RegisterTxCallback(uint32_t rfm22b_id, pios_com_callback tx_out_cb, uint32_t context);
|
||||
static void PIOS_RFM22B_COM_TxStart(uint32_t rfm22b_id, uint16_t tx_bytes_avail);
|
||||
static void PIOS_RFM22B_COM_RxStart(uint32_t rfm22b_id, uint16_t rx_bytes_avail);
|
||||
static bool PIOS_RFM22B_COM_Available(uint32_t rfm22b_com_id);
|
||||
|
||||
/* Local variables */
|
||||
const struct pios_com_driver pios_rfm22b_com_driver = {
|
||||
.set_baud = PIOS_RFM22B_COM_ChangeBaud,
|
||||
.tx_start = PIOS_RFM22B_COM_TxStart,
|
||||
.rx_start = PIOS_RFM22B_COM_RxStart,
|
||||
.bind_tx_cb = PIOS_RFM22B_COM_RegisterTxCallback,
|
||||
.bind_rx_cb = PIOS_RFM22B_COM_RegisterRxCallback,
|
||||
.available = PIOS_RFM22B_COM_Available
|
||||
};
|
||||
|
||||
/**
|
||||
* Changes the baud rate of the RFM22B peripheral without re-initialising.
|
||||
* \param[in] rfm22b_id RFM22B name (GPS, TELEM, AUX)
|
||||
* \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;
|
||||
// This is only allowed for coordinators.
|
||||
if (!rfm22b_dev->coordinator)
|
||||
return;
|
||||
// Set the RF data rate on the modem to ~2X the selected buad rate because the modem is half duplex.
|
||||
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_64000;
|
||||
else if (baud <= 57600)
|
||||
datarate = RFM22_datarate_128000;
|
||||
else if (baud <= 115200)
|
||||
datarate = RFM22_datarate_192000;
|
||||
PIOS_RFM22B_SetDatarate(rfm22b_id, datarate, true);
|
||||
}
|
||||
|
||||
static void PIOS_RFM22B_COM_RxStart(uint32_t rfm22b_id, uint16_t rx_bytes_avail)
|
||||
{
|
||||
}
|
||||
|
||||
static void PIOS_RFM22B_COM_TxStart(uint32_t rfm22b_id, uint16_t tx_bytes_avail)
|
||||
{
|
||||
struct pios_rfm22b_dev *rfm22b_dev = (struct pios_rfm22b_dev *)rfm22b_id;
|
||||
if (!PIOS_RFM22B_validate(rfm22b_dev))
|
||||
return;
|
||||
}
|
||||
|
||||
static void PIOS_RFM22B_COM_RegisterRxCallback(uint32_t rfm22b_id, pios_com_callback rx_in_cb, uint32_t context)
|
||||
{
|
||||
struct pios_rfm22b_dev *rfm22b_dev = (struct pios_rfm22b_dev *)rfm22b_id;
|
||||
if (!PIOS_RFM22B_validate(rfm22b_dev))
|
||||
return;
|
||||
|
||||
/*
|
||||
* Order is important in these assignments since ISR uses _cb
|
||||
* field to determine if it's ok to dereference _cb and _context
|
||||
*/
|
||||
rfm22b_dev->rx_in_context = context;
|
||||
rfm22b_dev->rx_in_cb = rx_in_cb;
|
||||
}
|
||||
|
||||
static void PIOS_RFM22B_COM_RegisterTxCallback(uint32_t rfm22b_id, pios_com_callback tx_out_cb, uint32_t context)
|
||||
{
|
||||
struct pios_rfm22b_dev *rfm22b_dev = (struct pios_rfm22b_dev *)rfm22b_id;
|
||||
if (!PIOS_RFM22B_validate(rfm22b_dev))
|
||||
return;
|
||||
|
||||
/*
|
||||
* Order is important in these assignments since ISR uses _cb
|
||||
* field to determine if it's ok to dereference _cb and _context
|
||||
*/
|
||||
rfm22b_dev->tx_out_context = context;
|
||||
rfm22b_dev->tx_out_cb = tx_out_cb;
|
||||
}
|
||||
|
||||
static bool PIOS_RFM22B_COM_Available(uint32_t rfm22b_id)
|
||||
{
|
||||
return PIOS_RFM22B_LinkStatus(rfm22b_id);
|
||||
}
|
99
flight/PiOS/Common/pios_rfm22b_rcvr.c
Normal file
99
flight/PiOS/Common/pios_rfm22b_rcvr.c
Normal file
@ -0,0 +1,99 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @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
|
||||
*/
|
||||
|
||||
/* Project Includes */
|
||||
#include "pios.h"
|
||||
|
||||
#if defined(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,
|
||||
};
|
||||
|
||||
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;
|
||||
}
|
||||
|
||||
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];
|
||||
}
|
||||
|
||||
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 * 1000 / 625))
|
||||
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] = 0;
|
||||
rfm22b_dev->ppm_fresh = false;
|
||||
}
|
||||
|
||||
#endif /* PIOS_INCLUDE_GCSRCVR */
|
||||
|
||||
/**
|
||||
* @}
|
||||
* @}
|
||||
*/
|
@ -223,7 +223,7 @@ bool PIOS_USB_CableConnected(uint8_t id)
|
||||
* \return 0: interface not available
|
||||
* \note Applications shouldn't call this function directly, instead please use \ref PIOS_COM layer functions
|
||||
*/
|
||||
bool PIOS_USB_CheckAvailable(uint8_t id)
|
||||
bool PIOS_USB_CheckAvailable(uint32_t id)
|
||||
{
|
||||
struct pios_usb_dev * usb_dev = (struct pios_usb_dev *) pios_usb_com_id;
|
||||
|
||||
|
@ -51,6 +51,7 @@ const struct pios_com_driver pios_usb_cdc_com_driver = {
|
||||
.rx_start = PIOS_USB_CDC_RxStart,
|
||||
.bind_tx_cb = PIOS_USB_CDC_RegisterTxCallback,
|
||||
.bind_rx_cb = PIOS_USB_CDC_RegisterRxCallback,
|
||||
.available = PIOS_USB_CheckAvailable,
|
||||
};
|
||||
|
||||
enum pios_usb_cdc_dev_magic {
|
||||
|
@ -51,6 +51,7 @@ const struct pios_com_driver pios_usb_hid_com_driver = {
|
||||
.rx_start = PIOS_USB_HID_RxStart,
|
||||
.bind_tx_cb = PIOS_USB_HID_RegisterTxCallback,
|
||||
.bind_rx_cb = PIOS_USB_HID_RegisterRxCallback,
|
||||
.available = PIOS_USB_CheckAvailable,
|
||||
};
|
||||
|
||||
enum pios_usb_hid_dev_magic {
|
||||
|
@ -155,7 +155,7 @@ int32_t PIOS_USB_ChangeConnectionState(bool connected)
|
||||
* \return 0: interface not available
|
||||
*/
|
||||
uint32_t usb_found;
|
||||
bool PIOS_USB_CheckAvailable(uint8_t id)
|
||||
bool PIOS_USB_CheckAvailable(uint32_t id)
|
||||
{
|
||||
struct pios_usb_dev * usb_dev = (struct pios_usb_dev *) pios_usb_id;
|
||||
|
||||
|
@ -48,6 +48,7 @@ const struct pios_com_driver pios_usb_cdc_com_driver = {
|
||||
.rx_start = PIOS_USB_CDC_RxStart,
|
||||
.bind_tx_cb = PIOS_USB_CDC_RegisterTxCallback,
|
||||
.bind_rx_cb = PIOS_USB_CDC_RegisterRxCallback,
|
||||
.available = PIOS_USB_CheckAvailable,
|
||||
};
|
||||
|
||||
enum pios_usb_cdc_dev_magic {
|
||||
|
@ -52,6 +52,7 @@ const struct pios_com_driver pios_usb_hid_com_driver = {
|
||||
.rx_start = PIOS_USB_HID_RxStart,
|
||||
.bind_tx_cb = PIOS_USB_HID_RegisterTxCallback,
|
||||
.bind_rx_cb = PIOS_USB_HID_RegisterRxCallback,
|
||||
.available = PIOS_USB_CheckAvailable,
|
||||
};
|
||||
|
||||
enum pios_usb_hid_dev_magic {
|
||||
|
@ -43,6 +43,7 @@ struct pios_com_driver {
|
||||
void (*rx_start)(uint32_t id, uint16_t rx_bytes_avail);
|
||||
void (*bind_rx_cb)(uint32_t id, pios_com_callback rx_in_cb, uint32_t context);
|
||||
void (*bind_tx_cb)(uint32_t id, pios_com_callback tx_out_cb, uint32_t context);
|
||||
bool (*available)(uint32_t id);
|
||||
};
|
||||
|
||||
/* Public Functions */
|
||||
@ -56,6 +57,7 @@ extern int32_t PIOS_COM_SendString(uint32_t com_id, const char *str);
|
||||
extern int32_t PIOS_COM_SendFormattedStringNonBlocking(uint32_t com_id, const char *format, ...);
|
||||
extern int32_t PIOS_COM_SendFormattedString(uint32_t com_id, const char *format, ...);
|
||||
extern uint16_t PIOS_COM_ReceiveBuffer(uint32_t com_id, uint8_t * buf, uint16_t buf_len, uint32_t timeout_ms);
|
||||
extern bool PIOS_COM_Available(uint32_t com_id);
|
||||
|
||||
#endif /* PIOS_COM_H */
|
||||
|
||||
|
@ -32,6 +32,7 @@
|
||||
#define PIOS_RFM22B_H
|
||||
|
||||
#include <packet_handler.h>
|
||||
#include <oplinksettings.h>
|
||||
|
||||
enum gpio_direction {GPIO0_TX_GPIO1_RX, GPIO0_RX_GPIO1_TX};
|
||||
|
||||
@ -39,12 +40,7 @@ enum gpio_direction {GPIO0_TX_GPIO1_RX, GPIO0_RX_GPIO1_TX};
|
||||
struct pios_rfm22b_cfg {
|
||||
const struct pios_spi_cfg * spi_cfg; /* Pointer to SPI interface configuration */
|
||||
const struct pios_exti_cfg * exti_cfg; /* Pointer to the EXTI configuration */
|
||||
uint32_t frequencyHz;
|
||||
uint32_t minFrequencyHz;
|
||||
uint32_t maxFrequencyHz;
|
||||
uint8_t RFXtalCap;
|
||||
uint32_t maxRFBandwidth;
|
||||
uint8_t maxTxPower;
|
||||
uint8_t slave_num;
|
||||
enum gpio_direction gpio_direction;
|
||||
};
|
||||
@ -77,18 +73,47 @@ enum rfm22b_datarate {
|
||||
RFM22_datarate_256000 = 13,
|
||||
};
|
||||
|
||||
struct rfm22b_stats {
|
||||
uint16_t packets_per_sec;
|
||||
uint16_t tx_byte_count;
|
||||
uint16_t rx_byte_count;
|
||||
uint16_t tx_seq;
|
||||
uint16_t rx_seq;
|
||||
uint8_t rx_good;
|
||||
uint8_t rx_corrected;
|
||||
uint8_t rx_error;
|
||||
uint8_t rx_missed;
|
||||
uint8_t rx_failure;
|
||||
uint8_t tx_dropped;
|
||||
uint8_t tx_resent;
|
||||
uint8_t tx_failure;
|
||||
uint8_t resets;
|
||||
uint8_t timeouts;
|
||||
uint8_t link_quality;
|
||||
int8_t rssi;
|
||||
int8_t afc_correction;
|
||||
uint8_t link_state;
|
||||
};
|
||||
|
||||
/* Callback function prototypes */
|
||||
typedef void (*PIOS_RFM22B_ComConfigCallback)(OPLinkSettingsOutputConnectionOptions com_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_SetFrequencyRange(uint32_t rfm22b_id, uint32_t min_frequency, uint32_t max_frequency);
|
||||
extern void PIOS_RFM22B_SetTxPower(uint32_t rfm22b_id, enum rfm22b_tx_power tx_pwr);
|
||||
extern void RFM22_SetDatarate(uint32_t rfm22b_id, enum rfm22b_datarate datarate, bool data_whitening);
|
||||
extern void PIOS_RFM22B_SetDatarate(uint32_t rfm22b_id, enum rfm22b_datarate datarate, bool data_whitening);
|
||||
extern void PIOS_RFM22B_SetDestinationId(uint32_t rfm22b_id, uint32_t dest_id);
|
||||
extern void PIOS_RFM22B_SetCoordinator(uint32_t rfm22b_id, bool coordinator);
|
||||
extern void PIOS_RFM22B_SetRemoteComConfig(uint32_t rfm22b_id, OPLinkSettingsOutputConnectionOptions com_port, OPLinkSettingsComSpeedOptions com_speed);
|
||||
extern void PIOS_RFM22B_SetComConfigCallback(uint32_t rfm22b_id, PIOS_RFM22B_ComConfigCallback cb);
|
||||
extern uint32_t PIOS_RFM22B_DeviceID(uint32_t rfb22b_id);
|
||||
extern uint16_t PIOS_RFM22B_Resets(uint32_t rfm22b_id);
|
||||
extern uint16_t PIOS_RFM22B_Timeouts(uint32_t rfm22b_id);
|
||||
extern uint8_t PIOS_RFM22B_LinkQuality(uint32_t rfm22b_id);
|
||||
extern int8_t PIOS_RFM22B_RSSI(uint32_t rfm22b_id);
|
||||
extern bool PIOS_RFM22B_Send_Packet(uint32_t rfm22b_id, PHPacketHandle p, uint32_t max_delay);
|
||||
extern uint32_t PIOS_RFM22B_Receive_Packet(uint32_t rfm22b_id, PHPacketHandle *p, uint32_t max_delay);
|
||||
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_LinkStatus(uint32_t rfm22b_id);
|
||||
|
||||
/* Global Variables */
|
||||
extern const struct pios_com_driver pios_rfm22b_com_driver;
|
||||
|
||||
#endif /* PIOS_RFM22B_H */
|
||||
|
||||
|
41
flight/PiOS/inc/pios_rfm22b_com.h
Normal file
41
flight/PiOS/inc/pios_rfm22b_com.h
Normal file
@ -0,0 +1,41 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup PIOS PIOS Core hardware abstraction layer
|
||||
* @{
|
||||
* @addtogroup PIOS_RFM22B COM Functions
|
||||
* @brief PIOS interface for RFM22B Radio COM interface
|
||||
* @{
|
||||
*
|
||||
* @file pios_rfm22b_com.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @brief RFM22B functions header.
|
||||
* @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_RFM22B_H
|
||||
#define PIOS_RFM22B_H
|
||||
|
||||
extern const struct pios_com_driver pios_rfm22b_com_driver;
|
||||
|
||||
#endif /* PIOS_RFM22B_H */
|
||||
|
||||
/**
|
||||
* @}
|
||||
* @}
|
||||
*/
|
@ -32,10 +32,11 @@
|
||||
#define PIOS_RFM22B_PRIV_H
|
||||
|
||||
#include <pios.h>
|
||||
#include "fifo_buffer.h"
|
||||
#include <fifo_buffer.h>
|
||||
#include <uavobjectmanager.h>
|
||||
#include <oplinkstatus.h>
|
||||
#include "pios_rfm22b.h"
|
||||
|
||||
extern const struct pios_com_driver pios_rfm22b_com_driver;
|
||||
#include "pios_rfm22b_rcvr.h"
|
||||
|
||||
// ************************************
|
||||
|
||||
@ -565,14 +566,239 @@ extern const struct pios_com_driver pios_rfm22b_com_driver;
|
||||
|
||||
#define RFM22_fifo_access 0x7F // R/W
|
||||
|
||||
// ************************************
|
||||
|
||||
typedef int16_t ( *t_rfm22_TxDataByteCallback ) (void);
|
||||
typedef bool ( *t_rfm22_RxDataCallback ) (void *data, uint8_t len);
|
||||
// External type definitions
|
||||
|
||||
// ************************************
|
||||
typedef int16_t (*t_rfm22_TxDataByteCallback) (void);
|
||||
typedef bool (*t_rfm22_RxDataCallback) (void *data, uint8_t len);
|
||||
enum pios_rfm22b_dev_magic {
|
||||
PIOS_RFM22B_DEV_MAGIC = 0x68e971b6,
|
||||
};
|
||||
|
||||
enum pios_rfm22b_state {
|
||||
RFM22B_STATE_UNINITIALIZED,
|
||||
RFM22B_STATE_INITIALIZING,
|
||||
RFM22B_STATE_INITIALIZED,
|
||||
RFM22B_STATE_INITIATING_CONNECTION,
|
||||
RFM22B_STATE_WAIT_FOR_CONNECTION,
|
||||
RFM22B_STATE_REQUESTING_CONNECTION,
|
||||
RFM22B_STATE_ACCEPTING_CONNECTION,
|
||||
RFM22B_STATE_CONNECTION_ACCEPTED,
|
||||
RFM22B_STATE_RX_MODE,
|
||||
RFM22B_STATE_WAIT_PREAMBLE,
|
||||
RFM22B_STATE_WAIT_SYNC,
|
||||
RFM22B_STATE_RX_DATA,
|
||||
RFM22B_STATE_RX_FAILURE,
|
||||
RFM22B_STATE_RECEIVING_STATUS,
|
||||
RFM22B_STATE_TX_START,
|
||||
RFM22B_STATE_TX_DATA,
|
||||
RFM22B_STATE_TX_FAILURE,
|
||||
RFM22B_STATE_SENDING_ACK,
|
||||
RFM22B_STATE_SENDING_NACK,
|
||||
RFM22B_STATE_RECEIVING_ACK,
|
||||
RFM22B_STATE_RECEIVING_NACK,
|
||||
RFM22B_STATE_TIMEOUT,
|
||||
RFM22B_STATE_ERROR,
|
||||
RFM22B_STATE_FATAL_ERROR,
|
||||
|
||||
RFM22B_STATE_NUM_STATES // Must be last
|
||||
};
|
||||
|
||||
enum pios_rfm22b_event {
|
||||
RFM22B_EVENT_INT_RECEIVED,
|
||||
RFM22B_EVENT_INITIALIZE,
|
||||
RFM22B_EVENT_INITIALIZED,
|
||||
RFM22B_EVENT_REQUEST_CONNECTION,
|
||||
RFM22B_EVENT_WAIT_FOR_CONNECTION,
|
||||
RFM22B_EVENT_CONNECTION_REQUESTED,
|
||||
RFM22B_EVENT_CONNECTION_ACCEPTED,
|
||||
RFM22B_EVENT_PACKET_ACKED,
|
||||
RFM22B_EVENT_PACKET_NACKED,
|
||||
RFM22B_EVENT_ACK_TIMEOUT,
|
||||
RFM22B_EVENT_RX_MODE,
|
||||
RFM22B_EVENT_PREAMBLE_DETECTED,
|
||||
RFM22B_EVENT_SYNC_DETECTED,
|
||||
RFM22B_EVENT_RX_COMPLETE,
|
||||
RFM22B_EVENT_RX_ERROR,
|
||||
RFM22B_EVENT_STATUS_RECEIVED,
|
||||
RFM22B_EVENT_TX_START,
|
||||
RFM22B_EVENT_FAILURE,
|
||||
RFM22B_EVENT_TIMEOUT,
|
||||
RFM22B_EVENT_ERROR,
|
||||
RFM22B_EVENT_FATAL_ERROR,
|
||||
|
||||
RFM22B_EVENT_NUM_EVENTS // Must be last
|
||||
};
|
||||
|
||||
#define RFM22B_RX_PACKET_STATS_LEN 4
|
||||
enum pios_rfm22b_rx_packet_status {
|
||||
RFM22B_GOOD_RX_PACKET = 0x00,
|
||||
RFM22B_CORRECTED_RX_PACKET = 0x01,
|
||||
RFM22B_ERROR_RX_PACKET = 0x2,
|
||||
RFM22B_RESENT_TX_PACKET = 0x3
|
||||
};
|
||||
|
||||
typedef struct {
|
||||
uint32_t pairID;
|
||||
int8_t rssi;
|
||||
int8_t afc_correction;
|
||||
uint8_t lastContact;
|
||||
} rfm22b_pair_stats;
|
||||
|
||||
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;
|
||||
|
||||
// The device ID
|
||||
uint32_t deviceID;
|
||||
|
||||
// The destination ID
|
||||
uint32_t destination_id;
|
||||
|
||||
// Is this device a coordinator?
|
||||
bool coordinator;
|
||||
|
||||
// The task handle
|
||||
xTaskHandle taskHandle;
|
||||
|
||||
// The potential paired statistics
|
||||
rfm22b_pair_stats pair_stats[OPLINKSTATUS_PAIRIDS_NUMELEM];
|
||||
|
||||
// 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;
|
||||
pios_com_callback tx_out_cb;
|
||||
uint32_t tx_out_context;
|
||||
|
||||
// the transmit power to use for data transmissions
|
||||
uint8_t tx_power;
|
||||
|
||||
// The RF datarate lookup index.
|
||||
uint8_t datarate;
|
||||
|
||||
// The state machine state and the current event
|
||||
enum pios_rfm22b_state state;
|
||||
|
||||
// The event queue handle
|
||||
xQueueHandle eventQueue;
|
||||
|
||||
// device status register
|
||||
uint8_t device_status;
|
||||
// interrupt status register 1
|
||||
uint8_t int_status1;
|
||||
// interrupt status register 2
|
||||
uint8_t int_status2;
|
||||
// ezmac status register
|
||||
uint8_t ezmac_status;
|
||||
|
||||
// The error statistics counters
|
||||
uint16_t prev_rx_seq_num;
|
||||
uint32_t rx_packet_stats[RFM22B_RX_PACKET_STATS_LEN];
|
||||
|
||||
// The packet statistics
|
||||
struct rfm22b_stats stats;
|
||||
|
||||
// Stats
|
||||
uint16_t errors;
|
||||
|
||||
// RSSI in dBm
|
||||
int8_t rssi_dBm;
|
||||
|
||||
// The packet queue handle
|
||||
xQueueHandle packetQueue;
|
||||
|
||||
// The tx data packet
|
||||
PHPacket data_packet;
|
||||
// The current tx packet
|
||||
PHPacketHandle tx_packet;
|
||||
// The previous tx packet (waiting for an ACK)
|
||||
PHPacketHandle prev_tx_packet;
|
||||
// The tx data read index
|
||||
uint16_t tx_data_rd;
|
||||
// The tx data write index
|
||||
uint16_t tx_data_wr;
|
||||
// The tx packet sequence number
|
||||
uint16_t tx_seq;
|
||||
|
||||
// The rx data packet
|
||||
PHPacket rx_packet;
|
||||
// The receive buffer write index
|
||||
uint16_t rx_buffer_wr;
|
||||
// The receive buffer write index
|
||||
uint16_t rx_packet_len;
|
||||
// Is the modem currently in Rx mode?
|
||||
bool in_rx_mode;
|
||||
|
||||
// The status packet
|
||||
PHStatusPacket status_packet;
|
||||
|
||||
// The ACK/NACK packet
|
||||
PHAckNackPacket ack_nack_packet;
|
||||
|
||||
#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 time_to_send;
|
||||
uint8_t time_to_send_offset;
|
||||
|
||||
// The minimum frequency
|
||||
uint32_t min_frequency;
|
||||
// The maximum frequency
|
||||
uint32_t max_frequency;
|
||||
// The current nominal frequency
|
||||
uint32_t frequency_hz;
|
||||
// The frequency hopping step size
|
||||
float frequency_step_size;
|
||||
// current frequency hop channel
|
||||
uint8_t frequency_hop_channel;
|
||||
// the frequency hop step size
|
||||
uint8_t frequency_hop_step_size_reg;
|
||||
// afc correction reading (in Hz)
|
||||
int8_t afc_correction_Hz;
|
||||
|
||||
// The maximum time (ms) that it should take to transmit / receive a packet.
|
||||
uint32_t max_packet_time;
|
||||
portTickType packet_start_ticks;
|
||||
portTickType tx_complete_ticks;
|
||||
portTickType rx_complete_ticks;
|
||||
uint8_t max_ack_delay;
|
||||
|
||||
// The PPM channel values
|
||||
uint16_t ppm_channel[PIOS_RFM22B_RCVR_MAX_CHANNELS];
|
||||
uint8_t ppm_supv_timer;
|
||||
bool ppm_fresh;
|
||||
};
|
||||
|
||||
|
||||
// External function definitions
|
||||
|
||||
bool PIOS_RFM22_EXT_Int(void);
|
||||
bool PIOS_RFM22B_validate(struct pios_rfm22b_dev * rfm22b_dev);
|
||||
void PIOS_RFM22B_InjectEvent(struct pios_rfm22b_dev *rfm22b_dev, enum pios_rfm22b_event event, bool inISR);
|
||||
|
||||
|
||||
// Global variable definitions
|
||||
|
||||
extern const struct pios_com_driver pios_rfm22b_com_driver;
|
||||
|
||||
#endif /* PIOS_RFM22B_PRIV_H */
|
||||
|
||||
|
@ -1,14 +1,13 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup OpenPilotModules OpenPilot Modules
|
||||
* @{
|
||||
* @addtogroup Radio Input / Output Module
|
||||
* @brief Read and Write packets from/to a radio device.
|
||||
* @{
|
||||
* @addtogroup PIOS PIOS Core hardware abstraction layer
|
||||
* @{
|
||||
* @addtogroup PIOS RFM22B Receiver Input Functions
|
||||
* @{
|
||||
*
|
||||
* @file radio.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @brief Include file of the radio module.
|
||||
* @file pios_rfm22b_rcvr.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @brief RFM22B Receiver Input functions header.
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
*
|
||||
*****************************************************************************/
|
||||
@ -28,12 +27,14 @@
|
||||
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
*/
|
||||
|
||||
#ifndef RADIOMODULE_H
|
||||
#define RADIOMODULE_H
|
||||
#ifndef PIOS_RFM22B_RCVR_H
|
||||
|
||||
#endif // RADIOMODULE_H
|
||||
#define PIOS_RFM22B_RCVR_MAX_CHANNELS 12
|
||||
|
||||
/**
|
||||
* @}
|
||||
* @}
|
||||
*/
|
||||
extern const struct pios_rcvr_driver pios_rfm22b_rcvr_driver;
|
||||
|
||||
extern int32_t PIOS_RFM22B_RCVR_Init(uint32_t rcvr_id);
|
||||
|
||||
#define PIOS_RFM22B_RCVR_H
|
||||
|
||||
#endif /* PIOS_RFM22B_RCVR_H */
|
@ -36,7 +36,7 @@
|
||||
extern int32_t PIOS_USB_Reenumerate();
|
||||
extern int32_t PIOS_USB_ChangeConnectionState(bool connected);
|
||||
extern bool PIOS_USB_CableConnected(uint8_t id);
|
||||
extern bool PIOS_USB_CheckAvailable(uint8_t id);
|
||||
extern bool PIOS_USB_CheckAvailable(uint32_t id);
|
||||
|
||||
#endif /* PIOS_USB_H */
|
||||
|
||||
|
@ -166,6 +166,16 @@
|
||||
#include <pios_usb.h>
|
||||
#endif
|
||||
|
||||
#if defined(PIOS_INCLUDE_RFM22B)
|
||||
#include <pios_rfm22b.h>
|
||||
#ifdef PIOS_INCLUDE_RFM22B_COM
|
||||
#include <pios_rfm22b_com.h>
|
||||
#endif
|
||||
#ifdef PIOS_INCLUDE_RFM22B_RCVR
|
||||
#include <pios_rfm22b_rcvr.h>
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#include <pios_crc.h>
|
||||
|
||||
#define NELEMENTS(x) (sizeof(x) / sizeof(*(x)))
|
||||
|
@ -73,7 +73,7 @@ FLASH_TOOL = OPENOCD
|
||||
|
||||
# List of modules to include
|
||||
OPTMODULES =
|
||||
MODULES = Radio RadioComBridge
|
||||
MODULES = RadioComBridge
|
||||
|
||||
# Paths
|
||||
OPSYSTEM = ./System
|
||||
@ -146,8 +146,8 @@ endif
|
||||
## UAVOBJECTS
|
||||
ifndef TESTAPP
|
||||
SRC += $(OPUAVSYNTHDIR)/gcsreceiver.c
|
||||
SRC += $(OPUAVSYNTHDIR)/pipxstatus.c
|
||||
SRC += $(OPUAVSYNTHDIR)/pipxsettings.c
|
||||
SRC += $(OPUAVSYNTHDIR)/oplinkstatus.c
|
||||
SRC += $(OPUAVSYNTHDIR)/oplinksettings.c
|
||||
SRC += $(OPUAVSYNTHDIR)/objectpersistence.c
|
||||
|
||||
endif
|
||||
@ -189,12 +189,12 @@ SRC += $(PIOSCOMMON)/pios_i2c_esc.c
|
||||
SRC += $(PIOSCOMMON)/pios_rcvr.c
|
||||
SRC += $(PIOSCOMMON)/printf-stdarg.c
|
||||
SRC += $(PIOSCOMMON)/pios_rfm22b.c
|
||||
SRC += $(PIOSCOMMON)/pios_rfm22b_com.c
|
||||
## Libraries for flight calculations
|
||||
SRC += $(FLIGHTLIB)/fifo_buffer.c
|
||||
SRC += $(FLIGHTLIB)/CoordinateConversions.c
|
||||
SRC += $(FLIGHTLIB)/taskmonitor.c
|
||||
SRC += $(FLIGHTLIB)/aes.c
|
||||
SRC += $(FLIGHTLIB)/packet_handler.c
|
||||
## The Reed-Solomon FEC library
|
||||
SRC += $(FLIGHTLIB)/rscode/rs.c
|
||||
SRC += $(FLIGHTLIB)/rscode/berlekamp.c
|
||||
|
@ -39,6 +39,7 @@
|
||||
#define PIOS_INCLUDE_LED
|
||||
#define PIOS_INCLUDE_IAP
|
||||
#define PIOS_INCLUDE_RFM22B
|
||||
#define PIOS_INCLUDE_RFM22B_COM
|
||||
#define PIOS_INCLUDE_RCVR
|
||||
#define PIOS_INCLUDE_TIM
|
||||
|
||||
@ -98,8 +99,8 @@
|
||||
/* PIOS Initcall infrastructure */
|
||||
#define PIOS_INCLUDE_INITCALL
|
||||
|
||||
/* Always include the radio module */
|
||||
#define RADIO_BUILTIN
|
||||
/* Turn on debugging signals on the telemetry port */
|
||||
//#define PIOS_RFM22B_DEBUG_ON_TELEM
|
||||
|
||||
#endif /* PIOS_CONFIG_H */
|
||||
/**
|
||||
|
@ -30,30 +30,34 @@
|
||||
|
||||
#include <pios.h>
|
||||
#include <openpilot.h>
|
||||
#include <pipxsettings.h>
|
||||
#include <oplinksettings.h>
|
||||
#include <board_hw_defs.c>
|
||||
|
||||
#define PIOS_COM_SERIAL_RX_BUF_LEN 256
|
||||
#define PIOS_COM_SERIAL_TX_BUF_LEN 256
|
||||
|
||||
#define PIOS_COM_FLEXI_RX_BUF_LEN 256
|
||||
#define PIOS_COM_FLEXI_TX_BUF_LEN 128
|
||||
#define PIOS_COM_TELEM_RX_BUF_LEN 256
|
||||
#define PIOS_COM_TELEM_TX_BUF_LEN 256
|
||||
|
||||
#define PIOS_COM_TELEM_USB_RX_BUF_LEN 256
|
||||
#define PIOS_COM_TELEM_USB_TX_BUF_LEN 256
|
||||
|
||||
#define PIOS_COM_VCP_USB_RX_BUF_LEN 256
|
||||
#define PIOS_COM_VCP_USB_TX_BUF_LEN 256
|
||||
#define PIOS_COM_TELEM_VCP_RX_BUF_LEN 256
|
||||
#define PIOS_COM_TELEM_VCP_TX_BUF_LEN 256
|
||||
|
||||
#define PIOS_COM_RFM22B_RF_RX_BUF_LEN 256
|
||||
#define PIOS_COM_RFM22B_RF_TX_BUF_LEN 256
|
||||
|
||||
uint32_t pios_com_telem_usb_id = 0;
|
||||
uint32_t pios_com_telemetry_id;
|
||||
uint32_t pios_com_flexi_id;
|
||||
uint32_t pios_com_vcp_id;
|
||||
uint32_t pios_com_uavtalk_com_id = 0;
|
||||
uint32_t pios_com_gcs_com_id = 0;
|
||||
uint32_t pios_com_trans_com_id = 0;
|
||||
uint32_t pios_com_debug_id = 0;
|
||||
uint32_t pios_com_telem_vcp_id = 0;
|
||||
uint32_t pios_com_telem_uart_telem_id = 0;
|
||||
uint32_t pios_com_telem_uart_flexi_id = 0;
|
||||
uint32_t pios_com_telemetry_id = 0;
|
||||
#if defined(PIOS_INCLUDE_PPM)
|
||||
uint32_t pios_ppm_rcvr_id = 0;
|
||||
#endif
|
||||
#if defined(PIOS_INCLUDE_RFM22B)
|
||||
uint32_t pios_rfm22b_id = 0;
|
||||
uint32_t pios_com_rfm22b_id = 0;
|
||||
uint32_t pios_com_radio_id = 0;
|
||||
#endif
|
||||
|
||||
/**
|
||||
* PIOS_Board_Init()
|
||||
@ -84,24 +88,24 @@ void PIOS_Board_Init(void) {
|
||||
PIOS_RTC_Init(&pios_rtc_main_cfg);
|
||||
#endif /* PIOS_INCLUDE_RTC */
|
||||
|
||||
PipXSettingsInitialize();
|
||||
OPLinkSettingsInitialize();
|
||||
|
||||
#if defined(PIOS_INCLUDE_LED)
|
||||
PIOS_LED_Init(&pios_led_cfg);
|
||||
#endif /* PIOS_INCLUDE_LED */
|
||||
|
||||
PipXSettingsData pipxSettings;
|
||||
OPLinkSettingsData oplinkSettings;
|
||||
#if defined(PIOS_INCLUDE_FLASH_EEPROM)
|
||||
PIOS_EEPROM_Init(&pios_eeprom_cfg);
|
||||
|
||||
/* Read the settings from flash. */
|
||||
/* NOTE: We probably need to save/restore the objID here incase the object changed but the size doesn't */
|
||||
if (PIOS_EEPROM_Load((uint8_t*)&pipxSettings, sizeof(PipXSettingsData)) == 0)
|
||||
PipXSettingsSet(&pipxSettings);
|
||||
if (PIOS_EEPROM_Load((uint8_t*)&oplinkSettings, sizeof(OPLinkSettingsData)) == 0)
|
||||
OPLinkSettingsSet(&oplinkSettings);
|
||||
else
|
||||
PipXSettingsGet(&pipxSettings);
|
||||
OPLinkSettingsGet(&oplinkSettings);
|
||||
#else
|
||||
PipXSettingsGet(&pipxSettings);
|
||||
OPLinkSettingsGet(&oplinkSettings);
|
||||
#endif /* PIOS_INCLUDE_FLASH_EEPROM */
|
||||
|
||||
/* Initialize the task monitor library */
|
||||
@ -115,11 +119,9 @@ void PIOS_Board_Init(void) {
|
||||
PIOS_TIM_InitClock(&tim_4_cfg);
|
||||
#endif /* PIOS_INCLUDE_TIM */
|
||||
|
||||
#if defined(PIOS_INCLUDE_USB)
|
||||
/* Initialize board specific USB data */
|
||||
PIOS_USB_BOARD_DATA_Init();
|
||||
|
||||
|
||||
/* Flags to determine if various USB interfaces are advertised */
|
||||
bool usb_cdc_present = false;
|
||||
|
||||
@ -134,60 +136,18 @@ void PIOS_Board_Init(void) {
|
||||
}
|
||||
#endif
|
||||
|
||||
/*Initialize the USB device */
|
||||
uint32_t pios_usb_id;
|
||||
PIOS_USB_Init(&pios_usb_id, &pios_usb_main_cfg);
|
||||
|
||||
#if defined(PIOS_INCLUDE_USB_CDC)
|
||||
if (!usb_cdc_present) {
|
||||
/* Force VCP port function to disabled if we haven't advertised VCP in our USB descriptor */
|
||||
pipxSettings.VCPConfig = PIPXSETTINGS_VCPCONFIG_DISABLED;
|
||||
}
|
||||
|
||||
switch (pipxSettings.VCPConfig)
|
||||
{
|
||||
case PIPXSETTINGS_VCPCONFIG_SERIAL:
|
||||
case PIPXSETTINGS_VCPCONFIG_DEBUG:
|
||||
{
|
||||
uint32_t pios_usb_cdc_id;
|
||||
if (PIOS_USB_CDC_Init(&pios_usb_cdc_id, &pios_usb_cdc_cfg, pios_usb_id)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
uint8_t * rx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_VCP_USB_RX_BUF_LEN);
|
||||
uint8_t * tx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_VCP_USB_TX_BUF_LEN);
|
||||
PIOS_Assert(rx_buffer);
|
||||
PIOS_Assert(tx_buffer);
|
||||
if (PIOS_COM_Init(&pios_com_vcp_id, &pios_usb_cdc_com_driver, pios_usb_cdc_id,
|
||||
rx_buffer, PIOS_COM_VCP_USB_RX_BUF_LEN,
|
||||
tx_buffer, PIOS_COM_VCP_USB_TX_BUF_LEN)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
switch (pipxSettings.VCPConfig)
|
||||
{
|
||||
case PIPXSETTINGS_VCPCONFIG_SERIAL:
|
||||
pios_com_trans_com_id = pios_com_vcp_id;
|
||||
break;
|
||||
case PIPXSETTINGS_VCPCONFIG_DEBUG:
|
||||
pios_com_debug_id = pios_com_vcp_id;
|
||||
break;
|
||||
}
|
||||
break;
|
||||
}
|
||||
case PIPXSETTINGS_VCPCONFIG_DISABLED:
|
||||
break;
|
||||
}
|
||||
#endif
|
||||
|
||||
#if defined(PIOS_INCLUDE_USB_HID)
|
||||
|
||||
/* Configure the usb HID port */
|
||||
#if defined(PIOS_INCLUDE_COM)
|
||||
/* Configure the USB HID port */
|
||||
{
|
||||
uint32_t pios_usb_hid_id;
|
||||
if (PIOS_USB_HID_Init(&pios_usb_hid_id, &pios_usb_hid_cfg, pios_usb_id)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
uint8_t * rx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_TELEM_USB_RX_BUF_LEN);
|
||||
uint8_t * tx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_TELEM_USB_TX_BUF_LEN);
|
||||
uint8_t *rx_buffer = (uint8_t *)pvPortMalloc(PIOS_COM_TELEM_USB_RX_BUF_LEN);
|
||||
uint8_t *tx_buffer = (uint8_t *)pvPortMalloc(PIOS_COM_TELEM_USB_TX_BUF_LEN);
|
||||
PIOS_Assert(rx_buffer);
|
||||
PIOS_Assert(tx_buffer);
|
||||
if (PIOS_COM_Init(&pios_com_telem_usb_id, &pios_usb_hid_com_driver, pios_usb_hid_id,
|
||||
@ -196,109 +156,97 @@ void PIOS_Board_Init(void) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_COM */
|
||||
|
||||
#endif /* PIOS_INCLUDE_USB_HID */
|
||||
|
||||
#endif /* PIOS_INCLUDE_USB */
|
||||
|
||||
/* Configure USART1 (telemetry port) */
|
||||
switch (pipxSettings.TelemetryConfig)
|
||||
/* Configure the USB virtual com port (VCP) */
|
||||
#if defined(PIOS_INCLUDE_USB_CDC)
|
||||
if (usb_cdc_present)
|
||||
{
|
||||
case PIPXSETTINGS_TELEMETRYCONFIG_SERIAL:
|
||||
case PIPXSETTINGS_TELEMETRYCONFIG_UAVTALK:
|
||||
case PIPXSETTINGS_TELEMETRYCONFIG_GCS:
|
||||
case PIPXSETTINGS_TELEMETRYCONFIG_DEBUG:
|
||||
uint32_t pios_usb_cdc_id;
|
||||
if (PIOS_USB_CDC_Init(&pios_usb_cdc_id, &pios_usb_cdc_cfg, pios_usb_id)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
uint8_t *rx_buffer = (uint8_t *)pvPortMalloc(PIOS_COM_TELEM_VCP_RX_BUF_LEN);
|
||||
uint8_t *tx_buffer = (uint8_t *)pvPortMalloc(PIOS_COM_TELEM_VCP_TX_BUF_LEN);
|
||||
PIOS_Assert(rx_buffer);
|
||||
PIOS_Assert(tx_buffer);
|
||||
if (PIOS_COM_Init(&pios_com_telem_vcp_id, &pios_usb_cdc_com_driver, pios_usb_cdc_id,
|
||||
rx_buffer, PIOS_COM_TELEM_VCP_RX_BUF_LEN,
|
||||
tx_buffer, PIOS_COM_TELEM_VCP_TX_BUF_LEN)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
/* Configure the telemetry serial port */
|
||||
#ifndef PIOS_RFM22B_DEBUG_ON_TELEM
|
||||
{
|
||||
uint32_t pios_usart1_id;
|
||||
if (PIOS_USART_Init(&pios_usart1_id, &pios_usart_serial_cfg)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
uint8_t * rx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_SERIAL_RX_BUF_LEN);
|
||||
uint8_t * tx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_SERIAL_TX_BUF_LEN);
|
||||
uint8_t *rx_buffer = (uint8_t *)pvPortMalloc(PIOS_COM_TELEM_RX_BUF_LEN);
|
||||
uint8_t *tx_buffer = (uint8_t *)pvPortMalloc(PIOS_COM_TELEM_TX_BUF_LEN);
|
||||
PIOS_Assert(rx_buffer);
|
||||
PIOS_Assert(tx_buffer);
|
||||
if (PIOS_COM_Init(&pios_com_telemetry_id, &pios_usart_com_driver, pios_usart1_id,
|
||||
rx_buffer, PIOS_COM_SERIAL_RX_BUF_LEN,
|
||||
tx_buffer, PIOS_COM_SERIAL_TX_BUF_LEN)) {
|
||||
if (PIOS_COM_Init(&pios_com_telem_uart_telem_id, &pios_usart_com_driver, pios_usart1_id,
|
||||
rx_buffer, PIOS_COM_TELEM_RX_BUF_LEN,
|
||||
tx_buffer, PIOS_COM_TELEM_TX_BUF_LEN)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
switch (pipxSettings.TelemetryConfig)
|
||||
{
|
||||
case PIPXSETTINGS_TELEMETRYCONFIG_SERIAL:
|
||||
pios_com_trans_com_id = pios_com_telemetry_id;
|
||||
break;
|
||||
case PIPXSETTINGS_TELEMETRYCONFIG_UAVTALK:
|
||||
pios_com_uavtalk_com_id = pios_com_telemetry_id;
|
||||
break;
|
||||
case PIPXSETTINGS_TELEMETRYCONFIG_GCS:
|
||||
pios_com_gcs_com_id = pios_com_telemetry_id;
|
||||
break;
|
||||
case PIPXSETTINGS_TELEMETRYCONFIG_DEBUG:
|
||||
pios_com_debug_id = pios_com_telemetry_id;
|
||||
break;
|
||||
}
|
||||
break;
|
||||
}
|
||||
case PIPXSETTINGS_TELEMETRYCONFIG_DISABLED:
|
||||
break;
|
||||
}
|
||||
#endif
|
||||
|
||||
/* Configure USART3 */
|
||||
switch (pipxSettings.FlexiConfig)
|
||||
/* Configure PPM input */
|
||||
#if defined(PIOS_INCLUDE_PPM)
|
||||
if (oplinkSettings.PPM == OPLINKSETTINGS_PPM_TRUE)
|
||||
{
|
||||
case PIPXSETTINGS_FLEXICONFIG_SERIAL:
|
||||
case PIPXSETTINGS_FLEXICONFIG_UAVTALK:
|
||||
case PIPXSETTINGS_FLEXICONFIG_GCS:
|
||||
case PIPXSETTINGS_FLEXICONFIG_DEBUG:
|
||||
uint32_t pios_ppm_id;
|
||||
PIOS_PPM_Init(&pios_ppm_id, &pios_ppm_cfg);
|
||||
|
||||
if (PIOS_RCVR_Init(&pios_ppm_rcvr_id, &pios_ppm_rcvr_driver, pios_ppm_id))
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
else
|
||||
#endif /* PIOS_INCLUDE_PPM */
|
||||
|
||||
/* Configure the flexi serial port */
|
||||
{
|
||||
uint32_t pios_usart3_id;
|
||||
if (PIOS_USART_Init(&pios_usart3_id, &pios_usart_telem_flexi_cfg)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
uint8_t * rx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_FLEXI_RX_BUF_LEN);
|
||||
uint8_t * tx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_FLEXI_TX_BUF_LEN);
|
||||
uint8_t * rx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_TELEM_RX_BUF_LEN);
|
||||
uint8_t * tx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_TELEM_TX_BUF_LEN);
|
||||
PIOS_Assert(rx_buffer);
|
||||
PIOS_Assert(tx_buffer);
|
||||
if (PIOS_COM_Init(&pios_com_flexi_id, &pios_usart_com_driver, pios_usart3_id,
|
||||
rx_buffer, PIOS_COM_FLEXI_RX_BUF_LEN,
|
||||
tx_buffer, PIOS_COM_FLEXI_TX_BUF_LEN)) {
|
||||
if (PIOS_COM_Init(&pios_com_telem_uart_flexi_id, &pios_usart_com_driver, pios_usart3_id,
|
||||
rx_buffer, PIOS_COM_TELEM_RX_BUF_LEN,
|
||||
tx_buffer, PIOS_COM_TELEM_TX_BUF_LEN)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
switch (pipxSettings.FlexiConfig)
|
||||
{
|
||||
case PIPXSETTINGS_FLEXICONFIG_SERIAL:
|
||||
pios_com_trans_com_id = pios_com_flexi_id;
|
||||
break;
|
||||
case PIPXSETTINGS_FLEXICONFIG_UAVTALK:
|
||||
pios_com_uavtalk_com_id = pios_com_flexi_id;
|
||||
break;
|
||||
case PIPXSETTINGS_FLEXICONFIG_GCS:
|
||||
pios_com_gcs_com_id = pios_com_flexi_id;
|
||||
break;
|
||||
case PIPXSETTINGS_FLEXICONFIG_DEBUG:
|
||||
pios_com_debug_id = pios_com_flexi_id;
|
||||
break;
|
||||
}
|
||||
break;
|
||||
}
|
||||
case PIPXSETTINGS_FLEXICONFIG_PPM_IN:
|
||||
#if defined(PIOS_INCLUDE_PPM)
|
||||
{
|
||||
uint32_t pios_ppm_id;
|
||||
PIOS_PPM_Init(&pios_ppm_id, &pios_ppm_cfg);
|
||||
|
||||
if (PIOS_RCVR_Init(&pios_ppm_rcvr_id, &pios_ppm_rcvr_driver, pios_ppm_id)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
/* Initalize the RFM22B radio COM device. */
|
||||
#if defined(PIOS_INCLUDE_RFM22B)
|
||||
{
|
||||
extern const struct pios_rfm22b_cfg * PIOS_BOARD_HW_DEFS_GetRfm22Cfg (uint32_t board_revision);
|
||||
const struct pios_board_info * bdinfo = &pios_board_info_blob;
|
||||
const struct pios_rfm22b_cfg *pios_rfm22b_cfg = PIOS_BOARD_HW_DEFS_GetRfm22Cfg(bdinfo->board_rev);
|
||||
if (PIOS_RFM22B_Init(&pios_rfm22b_id, PIOS_RFM22_SPI_PORT, pios_rfm22b_cfg->slave_num, pios_rfm22b_cfg)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
|
||||
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_rfm22b_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 /* PIOS_INCLUDE_PPM */
|
||||
break;
|
||||
case PIPXSETTINGS_FLEXICONFIG_PPM_OUT:
|
||||
case PIPXSETTINGS_FLEXICONFIG_RSSI:
|
||||
case PIPXSETTINGS_FLEXICONFIG_DISABLED:
|
||||
break;
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_RFM22B */
|
||||
|
||||
/* Remap AFIO pin */
|
||||
GPIO_PinRemapConfig( GPIO_Remap_SWJ_NoJTRST, ENABLE);
|
||||
|
@ -60,7 +60,6 @@ MODULES += AltitudeHold FixedWingPathFollower PathPlanner TxPID
|
||||
#MODULES += VtolPathFollower ## OP-700: VtolPathFollower disabled because its currently unsafe - remove this line once Sambas code has been merged
|
||||
MODULES += CameraStab
|
||||
#MODULES += OveroSync
|
||||
MODULES += Radio
|
||||
MODULES += Telemetry
|
||||
PYMODULES =
|
||||
#FlightPlan
|
||||
@ -152,7 +151,6 @@ SRC += $(MATHLIB)/sin_lookup.c
|
||||
SRC += $(MATHLIB)/pid.c
|
||||
|
||||
## For RFM22b
|
||||
SRC += $(FLIGHTLIB)/packet_handler.c
|
||||
SRC += $(RSCODE)/berlekamp.c
|
||||
SRC += $(RSCODE)/crcgen.c
|
||||
SRC += $(RSCODE)/galois.c
|
||||
@ -173,6 +171,8 @@ SRC += $(PIOSCOMMON)/pios_ms5611.c
|
||||
SRC += $(PIOSCOMMON)/pios_crc.c
|
||||
SRC += $(PIOSCOMMON)/pios_com.c
|
||||
SRC += $(PIOSCOMMON)/pios_rfm22b.c
|
||||
SRC += $(PIOSCOMMON)/pios_rfm22b_com.c
|
||||
SRC += $(PIOSCOMMON)/pios_rfm22b_rcvr.c
|
||||
SRC += $(PIOSCOMMON)/pios_rcvr.c
|
||||
SRC += $(PIOSCOMMON)/pios_sbus.c
|
||||
SRC += $(PIOSCOMMON)/pios_flash_jedec.c
|
||||
|
@ -58,8 +58,9 @@
|
||||
|
||||
/* Variables related to the RFM22B functionality */
|
||||
#define PIOS_INCLUDE_RFM22B
|
||||
#define RFM22_EXT_INT_USE
|
||||
|
||||
#define PIOS_INCLUDE_RFM22B_COM
|
||||
#define PIOS_INCLUDE_RFM22B_RCVR
|
||||
|
||||
/* Select the sensors to include */
|
||||
#define PIOS_INCLUDE_HMC5883
|
||||
#define PIOS_HMC5883_HAS_GPIOS
|
||||
@ -93,6 +94,8 @@
|
||||
/* A really shitty setting saving implementation */
|
||||
#define PIOS_INCLUDE_FLASH_SECTOR_SETTINGS
|
||||
|
||||
//#define PIOS_INCLUDE_DEBUG_CONSOLE
|
||||
|
||||
/* Other Interfaces */
|
||||
//#define PIOS_INCLUDE_I2C_ESC
|
||||
|
||||
|
@ -219,6 +219,9 @@ uint32_t pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_NONE];
|
||||
#define PIOS_COM_BRIDGE_RX_BUF_LEN 65
|
||||
#define PIOS_COM_BRIDGE_TX_BUF_LEN 12
|
||||
|
||||
#define PIOS_COM_RFM22B_RF_RX_BUF_LEN 512
|
||||
#define PIOS_COM_RFM22B_RF_TX_BUF_LEN 512
|
||||
|
||||
#if defined(PIOS_INCLUDE_DEBUG_CONSOLE)
|
||||
#define PIOS_COM_DEBUGCONSOLE_TX_BUF_LEN 40
|
||||
uint32_t pios_com_debug_id;
|
||||
@ -229,6 +232,9 @@ uint32_t pios_com_telem_usb_id = 0;
|
||||
uint32_t pios_com_telem_rf_id = 0;
|
||||
uint32_t pios_com_bridge_id = 0;
|
||||
uint32_t pios_com_overo_id = 0;
|
||||
#if defined(PIOS_INCLUDE_RFM22B)
|
||||
uint32_t pios_rfm22b_id = 0;
|
||||
#endif
|
||||
|
||||
/*
|
||||
* Setup a com port based on the passed cfg, driver and buffer sizes. tx size of -1 make the port rx only
|
||||
@ -522,7 +528,7 @@ void PIOS_Board_Init(void) {
|
||||
case HWSETTINGS_RM_MAINPORT_DEBUGCONSOLE:
|
||||
#if defined(PIOS_INCLUDE_DEBUG_CONSOLE)
|
||||
{
|
||||
PIOS_Board_configure_com(&pios_usart_main_cfg, 0, PIOS_COM_DEBUGCONSOLE_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_aux_id);
|
||||
PIOS_Board_configure_com(&pios_usart_main_cfg, 0, PIOS_COM_DEBUGCONSOLE_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_debug_id);
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_DEBUG_CONSOLE */
|
||||
break;
|
||||
@ -585,16 +591,53 @@ void PIOS_Board_Init(void) {
|
||||
case HWSETTINGS_RM_FLEXIPORT_DEBUGCONSOLE:
|
||||
#if defined(PIOS_INCLUDE_DEBUG_CONSOLE)
|
||||
{
|
||||
PIOS_Board_configure_com(&pios_usart_flexi_cfg, 0, PIOS_COM_DEBUGCONSOLE_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_aux_id);
|
||||
PIOS_Board_configure_com(&pios_usart_main_cfg, 0, PIOS_COM_DEBUGCONSOLE_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_debug_id);
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_DEBUG_CONSOLE */
|
||||
break;
|
||||
case HWSETTINGS_RM_FLEXIPORT_COMBRIDGE:
|
||||
PIOS_Board_configure_com(&pios_usart_flexi_cfg, PIOS_COM_BRIDGE_RX_BUF_LEN, PIOS_COM_BRIDGE_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_bridge_id);
|
||||
break;
|
||||
} /* hwsettings_rm_flexiport */
|
||||
|
||||
|
||||
} /* hwsettings_rv_flexiport */
|
||||
|
||||
/* Initalize the RFM22B radio COM device. */
|
||||
#if defined(PIOS_INCLUDE_RFM22B)
|
||||
uint8_t hwsettings_radioport;
|
||||
HwSettingsRadioPortGet(&hwsettings_radioport);
|
||||
switch (hwsettings_radioport) {
|
||||
case HWSETTINGS_RADIOPORT_DISABLED:
|
||||
break;
|
||||
case HWSETTINGS_RADIOPORT_TELEMETRY:
|
||||
{
|
||||
extern const struct pios_rfm22b_cfg * PIOS_BOARD_HW_DEFS_GetRfm22Cfg (uint32_t board_revision);
|
||||
const struct pios_board_info * bdinfo = &pios_board_info_blob;
|
||||
const struct pios_rfm22b_cfg *pios_rfm22b_cfg = PIOS_BOARD_HW_DEFS_GetRfm22Cfg(bdinfo->board_rev);
|
||||
if (PIOS_RFM22B_Init(&pios_rfm22b_id, PIOS_RFM22_SPI_PORT, pios_rfm22b_cfg->slave_num, pios_rfm22b_cfg)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
#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;
|
||||
}
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_RFM22B */
|
||||
|
||||
/* Configure the receiver port*/
|
||||
uint8_t hwsettings_rcvrport;
|
||||
HwSettingsRM_RcvrPortGet(&hwsettings_rcvrport);
|
||||
|
@ -97,11 +97,5 @@ UAVOBJSRCFILENAMES += waypointactive
|
||||
|
||||
UAVOBJSRCFILENAMES += txpidsettings
|
||||
|
||||
#Support for radio module on RM
|
||||
UAVOBJSRCFILENAMES += pipxstatus
|
||||
UAVOBJSRCFILENAMES += pipxsettings
|
||||
|
||||
|
||||
|
||||
UAVOBJSRC = $(foreach UAVOBJSRCFILE,$(UAVOBJSRCFILENAMES),$(UAVOBJSYNTHDIR)/$(UAVOBJSRCFILE).c )
|
||||
UAVOBJDEFINE = $(foreach UAVOBJSRCFILE,$(UAVOBJSRCFILENAMES),-DUAVOBJ_INIT_$(UAVOBJSRCFILE) )
|
||||
|
@ -59,6 +59,7 @@ 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);
|
||||
void UAVTalkGetStats(UAVTalkConnection connection, UAVTalkStats *stats);
|
||||
void UAVTalkResetStats(UAVTalkConnection connection);
|
||||
void UAVTalkGetLastTimestamp(UAVTalkConnection connection, uint16_t *timestamp);
|
||||
|
@ -558,6 +558,73 @@ UAVTalkRxState UAVTalkProcessInputStream(UAVTalkConnection connectionHandle, uin
|
||||
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.
|
||||
* \param[in] connection UAVTalkConnection to be used
|
||||
* \param[in] rxbyte Received byte
|
||||
* \return UAVTalkRxState
|
||||
*/
|
||||
UAVTalkRxState UAVTalkRelayInputStream(UAVTalkConnection connectionHandle, uint8_t rxbyte)
|
||||
{
|
||||
UAVTalkRxState state = UAVTalkProcessInputStreamQuiet(connectionHandle, rxbyte);
|
||||
|
||||
if (state == UAVTALK_STATE_COMPLETE)
|
||||
{
|
||||
UAVTalkConnectionData *connection;
|
||||
CHECKCONHANDLE(connectionHandle,connection,return -1);
|
||||
UAVTalkInputProcessor *iproc = &connection->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;
|
||||
}
|
||||
|
||||
return state;
|
||||
}
|
||||
|
||||
/**
|
||||
* Send a ACK through the telemetry link.
|
||||
* \param[in] connectionHandle UAVTalkConnection to be used
|
||||
|
@ -45,6 +45,48 @@ static const struct pios_led pios_leds[] = {
|
||||
},
|
||||
},
|
||||
},
|
||||
#ifdef PIOS_RFM22B_DEBUG_ON_TELEM
|
||||
[PIOS_LED_D1] = {
|
||||
.pin = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_14,
|
||||
.GPIO_Mode = GPIO_Mode_Out_PP,
|
||||
.GPIO_Speed = GPIO_Speed_50MHz,
|
||||
},
|
||||
},
|
||||
},
|
||||
[PIOS_LED_D2] = {
|
||||
.pin = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_15,
|
||||
.GPIO_Mode = GPIO_Mode_Out_PP,
|
||||
.GPIO_Speed = GPIO_Speed_50MHz,
|
||||
},
|
||||
},
|
||||
},
|
||||
[PIOS_LED_D3] = {
|
||||
.pin = {
|
||||
.gpio = GPIOA,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_9,
|
||||
.GPIO_Mode = GPIO_Mode_Out_PP,
|
||||
.GPIO_Speed = GPIO_Speed_50MHz,
|
||||
},
|
||||
},
|
||||
},
|
||||
[PIOS_LED_D4] = {
|
||||
.pin = {
|
||||
.gpio = GPIOA,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_10,
|
||||
.GPIO_Mode = GPIO_Mode_Out_PP,
|
||||
.GPIO_Speed = GPIO_Speed_50MHz,
|
||||
},
|
||||
},
|
||||
},
|
||||
#endif
|
||||
};
|
||||
|
||||
static const struct pios_led_cfg pios_led_cfg = {
|
||||
@ -222,12 +264,7 @@ static const struct pios_exti_cfg pios_exti_rfm22b_cfg __exti_config = {
|
||||
struct pios_rfm22b_cfg pios_rfm22b_pipx_cfg = {
|
||||
.spi_cfg = &pios_spi_rfm22b_cfg,
|
||||
.exti_cfg = &pios_exti_rfm22b_cfg,
|
||||
.frequencyHz = 434000000,
|
||||
.minFrequencyHz = 434000000 - 2000000,
|
||||
.maxFrequencyHz = 434000000 + 2000000,
|
||||
.RFXtalCap = 0x7f,
|
||||
.maxRFBandwidth = 64000,
|
||||
.maxTxPower = RFM22_tx_pwr_txpow_7, // +20dBm .. 100mW
|
||||
.slave_num = 0,
|
||||
.gpio_direction = GPIO0_TX_GPIO1_RX,
|
||||
};
|
||||
|
@ -522,12 +522,7 @@ static const struct pios_exti_cfg pios_exti_rfm22b_cfg __exti_config = {
|
||||
const struct pios_rfm22b_cfg pios_rfm22b_rm1_cfg = {
|
||||
.spi_cfg = &pios_spi_telem_flash_cfg,
|
||||
.exti_cfg = &pios_exti_rfm22b_cfg,
|
||||
.frequencyHz = 434000000,
|
||||
.minFrequencyHz = 434000000 - 2000000,
|
||||
.maxFrequencyHz = 434000000 + 2000000,
|
||||
.RFXtalCap = 0x7f,
|
||||
.maxRFBandwidth = 64000,
|
||||
.maxTxPower = RFM22_tx_pwr_txpow_7, // +20dBm .. 100mW
|
||||
.slave_num = 0,
|
||||
.gpio_direction = GPIO0_RX_GPIO1_TX,
|
||||
};
|
||||
@ -535,12 +530,7 @@ const struct pios_rfm22b_cfg pios_rfm22b_rm1_cfg = {
|
||||
const struct pios_rfm22b_cfg pios_rfm22b_rm2_cfg = {
|
||||
.spi_cfg = &pios_spi_telem_flash_cfg,
|
||||
.exti_cfg = &pios_exti_rfm22b_cfg,
|
||||
.frequencyHz = 434000000,
|
||||
.minFrequencyHz = 434000000 - 2000000,
|
||||
.maxFrequencyHz = 434000000 + 2000000,
|
||||
.RFXtalCap = 0x7f,
|
||||
.maxRFBandwidth = 64000,
|
||||
.maxTxPower = RFM22_tx_pwr_txpow_7, // +20dBm .. 100mW
|
||||
.slave_num = 0,
|
||||
.gpio_direction = GPIO0_TX_GPIO1_RX,
|
||||
};
|
||||
|
@ -140,17 +140,17 @@ ConfigGadgetWidget::ConfigGadgetWidget(QWidget *parent) : QWidget(parent)
|
||||
|
||||
// Connect to the PipXStatus object updates
|
||||
UAVObjectManager *objManager = pm->getObject<UAVObjectManager>();
|
||||
pipxStatusObj = dynamic_cast<UAVDataObject*>(objManager->getObject("PipXStatus"));
|
||||
if (pipxStatusObj != NULL ) {
|
||||
connect(pipxStatusObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(updatePipXStatus(UAVObject*)));
|
||||
oplinkStatusObj = dynamic_cast<UAVDataObject*>(objManager->getObject("OPLinkStatus"));
|
||||
if (oplinkStatusObj != NULL ) {
|
||||
connect(oplinkStatusObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(updateOPLinkStatus(UAVObject*)));
|
||||
} else {
|
||||
qDebug() << "Error: Object is unknown (PipXStatus).";
|
||||
qDebug() << "Error: Object is unknown (OPLinkStatus).";
|
||||
}
|
||||
|
||||
// Create the timer that is used to timeout the connection to the PipX.
|
||||
pipxTimeout = new QTimer(this);
|
||||
connect(pipxTimeout, SIGNAL(timeout()),this,SLOT(onPipxtremeDisconnect()));
|
||||
pipxConnected = false;
|
||||
// Create the timer that is used to timeout the connection to the OPLink.
|
||||
oplinkTimeout = new QTimer(this);
|
||||
connect(oplinkTimeout, SIGNAL(timeout()), this, SLOT(onOPLinkDisconnect()));
|
||||
oplinkConnected = false;
|
||||
}
|
||||
|
||||
ConfigGadgetWidget::~ConfigGadgetWidget()
|
||||
@ -268,29 +268,29 @@ void ConfigGadgetWidget::tabAboutToChange(int i, bool * proceed)
|
||||
}
|
||||
|
||||
/*!
|
||||
\brief Called by updates to @PipXStatus
|
||||
\brief Called by updates to @OPLinkStatus
|
||||
*/
|
||||
void ConfigGadgetWidget::updatePipXStatus(UAVObject *)
|
||||
void ConfigGadgetWidget::updateOPLinkStatus(UAVObject *)
|
||||
{
|
||||
// Restart the disconnection timer.
|
||||
pipxTimeout->start(5000);
|
||||
if (!pipxConnected)
|
||||
oplinkTimeout->start(5000);
|
||||
if (!oplinkConnected)
|
||||
{
|
||||
qDebug() << "ConfigGadgetWidget onPipxtremeConnect";
|
||||
qDebug() << "ConfigGadgetWidget onOPLinkConnect";
|
||||
|
||||
QIcon *icon = new QIcon();
|
||||
icon->addFile(":/configgadget/images/pipx-normal.png", QSize(), QIcon::Normal, QIcon::Off);
|
||||
icon->addFile(":/configgadget/images/pipx-selected.png", QSize(), QIcon::Selected, QIcon::Off);
|
||||
|
||||
QWidget *qwd = new ConfigPipXtremeWidget(this);
|
||||
ftw->insertTab(ConfigGadgetWidget::pipxtreme, qwd, *icon, QString("OPLink"));
|
||||
pipxConnected = true;
|
||||
ftw->insertTab(ConfigGadgetWidget::oplink, qwd, *icon, QString("OPLink"));
|
||||
oplinkConnected = true;
|
||||
}
|
||||
}
|
||||
|
||||
void ConfigGadgetWidget::onPipxtremeDisconnect() {
|
||||
qDebug()<<"ConfigGadgetWidget onPipxtremeDisconnect";
|
||||
pipxTimeout->stop();
|
||||
ftw->removeTab(ConfigGadgetWidget::pipxtreme);
|
||||
pipxConnected = false;
|
||||
void ConfigGadgetWidget::onOPLinkDisconnect() {
|
||||
qDebug()<<"ConfigGadgetWidget onOPLinkDisconnect";
|
||||
oplinkTimeout->stop();
|
||||
ftw->removeTab(ConfigGadgetWidget::oplink);
|
||||
oplinkConnected = false;
|
||||
}
|
||||
|
@ -48,32 +48,32 @@ class ConfigGadgetWidget: public QWidget
|
||||
public:
|
||||
ConfigGadgetWidget(QWidget *parent = 0);
|
||||
~ConfigGadgetWidget();
|
||||
enum widgetTabs {hardware=0, aircraft, input, output, sensors, stabilization, camerastabilization, txpid, pipxtreme, autotune};
|
||||
enum widgetTabs {hardware=0, aircraft, input, output, sensors, stabilization, camerastabilization, txpid, oplink, autotune};
|
||||
void startInputWizard();
|
||||
|
||||
public slots:
|
||||
void onAutopilotConnect();
|
||||
void onAutopilotDisconnect();
|
||||
void tabAboutToChange(int i,bool *);
|
||||
void updatePipXStatus(UAVObject *object);
|
||||
void onPipxtremeDisconnect();
|
||||
void updateOPLinkStatus(UAVObject *object);
|
||||
void onOPLinkDisconnect();
|
||||
|
||||
signals:
|
||||
void autopilotConnected();
|
||||
void autopilotDisconnected();
|
||||
void pipxtremeConnect();
|
||||
void pipxtremeDisconnect();
|
||||
void oplinkConnect();
|
||||
void oplinkDisconnect();
|
||||
|
||||
protected:
|
||||
void resizeEvent(QResizeEvent * event);
|
||||
MyTabbedStackWidget *ftw;
|
||||
|
||||
private:
|
||||
UAVDataObject* pipxStatusObj;
|
||||
UAVDataObject* oplinkStatusObj;
|
||||
|
||||
// A timer that timesout the connction to the PipX.
|
||||
QTimer *pipxTimeout;
|
||||
bool pipxConnected;
|
||||
// A timer that timesout the connction to the OPLink.
|
||||
QTimer *oplinkTimeout;
|
||||
bool oplinkConnected;
|
||||
};
|
||||
|
||||
#endif // CONFIGGADGETWIDGET_H
|
||||
|
@ -27,77 +27,81 @@
|
||||
|
||||
#include "configpipxtremewidget.h"
|
||||
|
||||
#include <pipxsettings.h>
|
||||
#include <pipxstatus.h>
|
||||
#include <oplinksettings.h>
|
||||
#include <oplinkstatus.h>
|
||||
|
||||
ConfigPipXtremeWidget::ConfigPipXtremeWidget(QWidget *parent) : ConfigTaskWidget(parent)
|
||||
{
|
||||
m_pipx = new Ui_PipXtremeWidget();
|
||||
m_pipx->setupUi(this);
|
||||
m_oplink = new Ui_PipXtremeWidget();
|
||||
m_oplink->setupUi(this);
|
||||
|
||||
// Connect to the PipXStatus object updates
|
||||
// Connect to the OPLinkStatus object updates
|
||||
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
|
||||
UAVObjectManager *objManager = pm->getObject<UAVObjectManager>();
|
||||
pipxStatusObj = dynamic_cast<UAVDataObject*>(objManager->getObject("PipXStatus"));
|
||||
if (pipxStatusObj != NULL ) {
|
||||
connect(pipxStatusObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(updateStatus(UAVObject*)));
|
||||
oplinkStatusObj = dynamic_cast<UAVDataObject*>(objManager->getObject("OPLinkStatus"));
|
||||
if (oplinkStatusObj != NULL ) {
|
||||
connect(oplinkStatusObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(updateStatus(UAVObject*)));
|
||||
} else {
|
||||
qDebug() << "Error: Object is unknown (PipXStatus).";
|
||||
qDebug() << "Error: Object is unknown (OPLinkStatus).";
|
||||
}
|
||||
|
||||
// Connect to the PipXSettings object updates
|
||||
pipxSettingsObj = dynamic_cast<UAVDataObject*>(objManager->getObject("PipXSettings"));
|
||||
if (pipxSettingsObj != NULL ) {
|
||||
connect(pipxSettingsObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(updateSettings(UAVObject*)));
|
||||
// Connect to the OPLinkSettings object updates
|
||||
oplinkSettingsObj = dynamic_cast<UAVDataObject*>(objManager->getObject("OPLinkSettings"));
|
||||
if (oplinkSettingsObj != NULL ) {
|
||||
connect(oplinkSettingsObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(updateSettings(UAVObject*)));
|
||||
} else {
|
||||
qDebug() << "Error: Object is unknown (PipXSettings).";
|
||||
qDebug() << "Error: Object is unknown (OPLinkSettings).";
|
||||
}
|
||||
autoLoadWidgets();
|
||||
addApplySaveButtons(m_pipx->Apply, m_pipx->Save);
|
||||
addApplySaveButtons(m_oplink->Apply, m_oplink->Save);
|
||||
|
||||
addUAVObjectToWidgetRelation("PipXSettings", "TelemetryConfig", m_pipx->TelemPortConfig);
|
||||
addUAVObjectToWidgetRelation("PipXSettings", "TelemetrySpeed", m_pipx->TelemPortSpeed);
|
||||
addUAVObjectToWidgetRelation("PipXSettings", "FlexiConfig", m_pipx->FlexiPortConfig);
|
||||
addUAVObjectToWidgetRelation("PipXSettings", "FlexiSpeed", m_pipx->FlexiPortSpeed);
|
||||
addUAVObjectToWidgetRelation("PipXSettings", "VCPConfig", m_pipx->VCPConfig);
|
||||
addUAVObjectToWidgetRelation("PipXSettings", "VCPSpeed", m_pipx->VCPSpeed);
|
||||
addUAVObjectToWidgetRelation("PipXSettings", "RFSpeed", m_pipx->MaxRFDatarate);
|
||||
addUAVObjectToWidgetRelation("PipXSettings", "MaxRFPower", m_pipx->MaxRFTxPower);
|
||||
addUAVObjectToWidgetRelation("PipXSettings", "SendTimeout", m_pipx->SendTimeout);
|
||||
addUAVObjectToWidgetRelation("PipXSettings", "MinPacketSize", m_pipx->MinPacketSize);
|
||||
addUAVObjectToWidgetRelation("PipXSettings", "FrequencyCalibration", m_pipx->FrequencyCalibration);
|
||||
addUAVObjectToWidgetRelation("PipXSettings", "Frequency", m_pipx->Frequency);
|
||||
addUAVObjectToWidgetRelation("OPLinkSettings", "Coordinator", m_oplink->Coordinator);
|
||||
addUAVObjectToWidgetRelation("OPLinkSettings", "PPM", m_oplink->PPM);
|
||||
addUAVObjectToWidgetRelation("OPLinkSettings", "UAVTalk", m_oplink->UAVTalk);
|
||||
addUAVObjectToWidgetRelation("OPLinkSettings", "InputConnection", m_oplink->InputConnection);
|
||||
addUAVObjectToWidgetRelation("OPLinkSettings", "OutputConnection", m_oplink->OutputConnection);
|
||||
addUAVObjectToWidgetRelation("OPLinkSettings", "ComSpeed", m_oplink->ComSpeed);
|
||||
addUAVObjectToWidgetRelation("OPLinkSettings", "MaxRFPower", m_oplink->MaxRFTxPower);
|
||||
addUAVObjectToWidgetRelation("OPLinkSettings", "SendTimeout", m_oplink->SendTimeout);
|
||||
addUAVObjectToWidgetRelation("OPLinkSettings", "MinPacketSize", m_oplink->MinPacketSize);
|
||||
addUAVObjectToWidgetRelation("OPLinkSettings", "FrequencyCalibration", m_oplink->FrequencyCalibration);
|
||||
addUAVObjectToWidgetRelation("OPLinkSettings", "MinFrequency", m_oplink->MinFrequency);
|
||||
addUAVObjectToWidgetRelation("OPLinkSettings", "MaxFrequency", m_oplink->MaxFrequency);
|
||||
|
||||
addUAVObjectToWidgetRelation("PipXStatus", "MinFrequency", m_pipx->MinFrequency);
|
||||
addUAVObjectToWidgetRelation("PipXStatus", "MaxFrequency", m_pipx->MaxFrequency);
|
||||
addUAVObjectToWidgetRelation("PipXStatus", "FrequencyStepSize", m_pipx->FrequencyStepSize);
|
||||
addUAVObjectToWidgetRelation("PipXStatus", "FrequencyBand", m_pipx->FreqBand);
|
||||
addUAVObjectToWidgetRelation("PipXStatus", "RSSI", m_pipx->RSSI);
|
||||
addUAVObjectToWidgetRelation("PipXStatus", "AFC", m_pipx->RxAFC);
|
||||
addUAVObjectToWidgetRelation("PipXStatus", "Retries", m_pipx->Retries);
|
||||
addUAVObjectToWidgetRelation("PipXStatus", "LinkQuality", m_pipx->LinkQuality);
|
||||
addUAVObjectToWidgetRelation("PipXStatus", "UAVTalkErrors", m_pipx->UAVTalkErrors);
|
||||
addUAVObjectToWidgetRelation("PipXStatus", "Resets", m_pipx->Resets);
|
||||
addUAVObjectToWidgetRelation("PipXStatus", "Dropped", m_pipx->Dropped);
|
||||
addUAVObjectToWidgetRelation("PipXStatus", "RXRate", m_pipx->RXRate);
|
||||
addUAVObjectToWidgetRelation("PipXStatus", "TXRate", m_pipx->TXRate);
|
||||
addUAVObjectToWidgetRelation("OPLinkStatus", "RxGood", m_oplink->Good);
|
||||
addUAVObjectToWidgetRelation("OPLinkStatus", "RxCorrected", m_oplink->Corrected);
|
||||
addUAVObjectToWidgetRelation("OPLinkStatus", "RxErrors", m_oplink->Errors);
|
||||
addUAVObjectToWidgetRelation("OPLinkStatus", "RxMissed", m_oplink->Missed);
|
||||
addUAVObjectToWidgetRelation("OPLinkStatus", "RxFailure", m_oplink->RxFailure);
|
||||
addUAVObjectToWidgetRelation("OPLinkStatus", "UAVTalkErrors", m_oplink->UAVTalkErrors);
|
||||
addUAVObjectToWidgetRelation("OPLinkStatus", "TxDropped", m_oplink->Dropped);
|
||||
addUAVObjectToWidgetRelation("OPLinkStatus", "TxResent", m_oplink->Resent);
|
||||
addUAVObjectToWidgetRelation("OPLinkStatus", "TxFailure", m_oplink->TxFailure);
|
||||
addUAVObjectToWidgetRelation("OPLinkStatus", "Resets", m_oplink->Resets);
|
||||
addUAVObjectToWidgetRelation("OPLinkStatus", "Timeouts", m_oplink->Timeouts);
|
||||
addUAVObjectToWidgetRelation("OPLinkStatus", "RSSI", m_oplink->RSSI);
|
||||
addUAVObjectToWidgetRelation("OPLinkStatus", "AFCCorrection", m_oplink->AFCCorrection);
|
||||
addUAVObjectToWidgetRelation("OPLinkStatus", "LinkQuality", m_oplink->LinkQuality);
|
||||
addUAVObjectToWidgetRelation("OPLinkStatus", "RXSeq", m_oplink->RXSeq);
|
||||
addUAVObjectToWidgetRelation("OPLinkStatus", "TXSeq", m_oplink->TXSeq);
|
||||
addUAVObjectToWidgetRelation("OPLinkStatus", "RXRate", m_oplink->RXRate);
|
||||
addUAVObjectToWidgetRelation("OPLinkStatus", "TXRate", m_oplink->TXRate);
|
||||
|
||||
// Connect to the pair ID radio buttons.
|
||||
connect(m_pipx->PairSelectB, SIGNAL(toggled(bool)), this, SLOT(pairBToggled(bool)));
|
||||
connect(m_pipx->PairSelect1, SIGNAL(toggled(bool)), this, SLOT(pair1Toggled(bool)));
|
||||
connect(m_pipx->PairSelect2, SIGNAL(toggled(bool)), this, SLOT(pair2Toggled(bool)));
|
||||
connect(m_pipx->PairSelect3, SIGNAL(toggled(bool)), this, SLOT(pair3Toggled(bool)));
|
||||
connect(m_pipx->PairSelect4, SIGNAL(toggled(bool)), this, SLOT(pair4Toggled(bool)));
|
||||
connect(m_oplink->PairSelectB, SIGNAL(toggled(bool)), this, SLOT(pairBToggled(bool)));
|
||||
connect(m_oplink->PairSelect1, SIGNAL(toggled(bool)), this, SLOT(pair1Toggled(bool)));
|
||||
connect(m_oplink->PairSelect2, SIGNAL(toggled(bool)), this, SLOT(pair2Toggled(bool)));
|
||||
connect(m_oplink->PairSelect3, SIGNAL(toggled(bool)), this, SLOT(pair3Toggled(bool)));
|
||||
connect(m_oplink->PairSelect4, SIGNAL(toggled(bool)), this, SLOT(pair4Toggled(bool)));
|
||||
|
||||
//Add scroll bar when necessary
|
||||
QScrollArea *scroll = new QScrollArea;
|
||||
scroll->setWidget(m_pipx->frame_3);
|
||||
scroll->setWidget(m_oplink->frame_3);
|
||||
scroll->setWidgetResizable(true);
|
||||
m_pipx->verticalLayout_3->addWidget(scroll);
|
||||
m_oplink->verticalLayout_3->addWidget(scroll);
|
||||
|
||||
// Request and update of the setting object.
|
||||
settingsUpdated = false;
|
||||
//pipxSettingsObj->requestUpdate();
|
||||
|
||||
disableMouseWheelEvents();
|
||||
}
|
||||
@ -113,84 +117,84 @@ void ConfigPipXtremeWidget::refreshValues()
|
||||
|
||||
void ConfigPipXtremeWidget::applySettings()
|
||||
{
|
||||
PipXSettings *pipxSettings = PipXSettings::GetInstance(getObjectManager());
|
||||
PipXSettings::DataFields pipxSettingsData = pipxSettings->getData();
|
||||
OPLinkSettings *oplinkSettings = OPLinkSettings::GetInstance(getObjectManager());
|
||||
OPLinkSettings::DataFields oplinkSettingsData = oplinkSettings->getData();
|
||||
|
||||
// Get the pair ID.
|
||||
quint32 pairID = 0;
|
||||
bool okay;
|
||||
if (m_pipx->PairSelect1->isChecked())
|
||||
pairID = m_pipx->PairID1->text().toUInt(&okay, 16);
|
||||
else if (m_pipx->PairSelect2->isChecked())
|
||||
pairID = m_pipx->PairID2->text().toUInt(&okay, 16);
|
||||
else if (m_pipx->PairSelect3->isChecked())
|
||||
pairID = m_pipx->PairID3->text().toUInt(&okay, 16);
|
||||
else if (m_pipx->PairSelect4->isChecked())
|
||||
pairID = m_pipx->PairID4->text().toUInt(&okay, 16);
|
||||
pipxSettingsData.PairID = pairID;
|
||||
pipxSettings->setData(pipxSettingsData);
|
||||
if (m_oplink->PairSelect1->isChecked())
|
||||
pairID = m_oplink->PairID1->text().toUInt(&okay, 16);
|
||||
else if (m_oplink->PairSelect2->isChecked())
|
||||
pairID = m_oplink->PairID2->text().toUInt(&okay, 16);
|
||||
else if (m_oplink->PairSelect3->isChecked())
|
||||
pairID = m_oplink->PairID3->text().toUInt(&okay, 16);
|
||||
else if (m_oplink->PairSelect4->isChecked())
|
||||
pairID = m_oplink->PairID4->text().toUInt(&okay, 16);
|
||||
oplinkSettingsData.PairID = pairID;
|
||||
oplinkSettings->setData(oplinkSettingsData);
|
||||
}
|
||||
|
||||
void ConfigPipXtremeWidget::saveSettings()
|
||||
{
|
||||
//applySettings();
|
||||
UAVObject *obj = PipXSettings::GetInstance(getObjectManager());
|
||||
UAVObject *obj = OPLinkSettings::GetInstance(getObjectManager());
|
||||
saveObjectToSD(obj);
|
||||
}
|
||||
|
||||
/*!
|
||||
\brief Called by updates to @PipXStatus
|
||||
\brief Called by updates to @OPLinkStatus
|
||||
*/
|
||||
void ConfigPipXtremeWidget::updateStatus(UAVObject *object)
|
||||
{
|
||||
|
||||
// Request and update of the setting object if we haven't received it yet.
|
||||
if (!settingsUpdated)
|
||||
pipxSettingsObj->requestUpdate();
|
||||
oplinkSettingsObj->requestUpdate();
|
||||
|
||||
// Get the current pairID
|
||||
PipXSettings *pipxSettings = PipXSettings::GetInstance(getObjectManager());
|
||||
OPLinkSettings *oplinkSettings = OPLinkSettings::GetInstance(getObjectManager());
|
||||
quint32 pairID = 0;
|
||||
if (pipxSettings)
|
||||
pairID = pipxSettings->getPairID();
|
||||
if (oplinkSettings)
|
||||
pairID = oplinkSettings->getPairID();
|
||||
|
||||
// Update the detected devices.
|
||||
UAVObjectField* pairIdField = object->getField("PairIDs");
|
||||
if (pairIdField) {
|
||||
quint32 pairid1 = pairIdField->getValue(0).toUInt();
|
||||
m_pipx->PairID1->setText(QString::number(pairid1, 16).toUpper());
|
||||
m_pipx->PairID1->setEnabled(false);
|
||||
m_pipx->PairSelect1->setChecked(pairID && (pairID == pairid1));
|
||||
m_pipx->PairSelect1->setEnabled(pairid1);
|
||||
m_oplink->PairID1->setText(QString::number(pairid1, 16).toUpper());
|
||||
m_oplink->PairID1->setEnabled(false);
|
||||
m_oplink->PairSelect1->setChecked(pairID && (pairID == pairid1));
|
||||
m_oplink->PairSelect1->setEnabled(pairid1);
|
||||
quint32 pairid2 = pairIdField->getValue(1).toUInt();
|
||||
m_pipx->PairID2->setText(QString::number(pairIdField->getValue(1).toUInt(), 16).toUpper());
|
||||
m_pipx->PairID2->setEnabled(false);
|
||||
m_pipx->PairSelect2->setChecked(pairID && (pairID == pairid2));
|
||||
m_pipx->PairSelect2->setEnabled(pairid2);
|
||||
m_oplink->PairID2->setText(QString::number(pairIdField->getValue(1).toUInt(), 16).toUpper());
|
||||
m_oplink->PairID2->setEnabled(false);
|
||||
m_oplink->PairSelect2->setChecked(pairID && (pairID == pairid2));
|
||||
m_oplink->PairSelect2->setEnabled(pairid2);
|
||||
quint32 pairid3 = pairIdField->getValue(2).toUInt();
|
||||
m_pipx->PairID3->setText(QString::number(pairIdField->getValue(2).toUInt(), 16).toUpper());
|
||||
m_pipx->PairID3->setEnabled(false);
|
||||
m_pipx->PairSelect3->setChecked(pairID && (pairID == pairid3));
|
||||
m_pipx->PairSelect3->setEnabled(pairid3);
|
||||
m_oplink->PairID3->setText(QString::number(pairIdField->getValue(2).toUInt(), 16).toUpper());
|
||||
m_oplink->PairID3->setEnabled(false);
|
||||
m_oplink->PairSelect3->setChecked(pairID && (pairID == pairid3));
|
||||
m_oplink->PairSelect3->setEnabled(pairid3);
|
||||
quint32 pairid4 = pairIdField->getValue(3).toUInt();
|
||||
m_pipx->PairID4->setText(QString::number(pairIdField->getValue(3).toUInt(), 16).toUpper());
|
||||
m_pipx->PairID4->setEnabled(false);
|
||||
m_pipx->PairSelect4->setChecked(pairID && (pairID == pairid4));
|
||||
m_pipx->PairSelect4->setEnabled(pairid4);
|
||||
m_oplink->PairID4->setText(QString::number(pairIdField->getValue(3).toUInt(), 16).toUpper());
|
||||
m_oplink->PairID4->setEnabled(false);
|
||||
m_oplink->PairSelect4->setChecked(pairID && (pairID == pairid4));
|
||||
m_oplink->PairSelect4->setEnabled(pairid4);
|
||||
} else {
|
||||
qDebug() << "PipXtremeGadgetWidget: Count not read PairID field.";
|
||||
}
|
||||
UAVObjectField* pairRssiField = object->getField("PairSignalStrengths");
|
||||
if (pairRssiField) {
|
||||
m_pipx->PairSignalStrengthBar1->setValue(pairRssiField->getValue(0).toInt());
|
||||
m_pipx->PairSignalStrengthBar2->setValue(pairRssiField->getValue(1).toInt());
|
||||
m_pipx->PairSignalStrengthBar3->setValue(pairRssiField->getValue(2).toInt());
|
||||
m_pipx->PairSignalStrengthBar4->setValue(pairRssiField->getValue(3).toInt());
|
||||
m_pipx->PairSignalStrengthLabel1->setText(QString("%1dB").arg(pairRssiField->getValue(0).toInt()));
|
||||
m_pipx->PairSignalStrengthLabel2->setText(QString("%1dB").arg(pairRssiField->getValue(1).toInt()));
|
||||
m_pipx->PairSignalStrengthLabel3->setText(QString("%1dB").arg(pairRssiField->getValue(2).toInt()));
|
||||
m_pipx->PairSignalStrengthLabel4->setText(QString("%1dB").arg(pairRssiField->getValue(3).toInt()));
|
||||
} else {
|
||||
m_oplink->PairSignalStrengthBar1->setValue(pairRssiField->getValue(0).toInt());
|
||||
m_oplink->PairSignalStrengthBar2->setValue(pairRssiField->getValue(1).toInt());
|
||||
m_oplink->PairSignalStrengthBar3->setValue(pairRssiField->getValue(2).toInt());
|
||||
m_oplink->PairSignalStrengthBar4->setValue(pairRssiField->getValue(3).toInt());
|
||||
m_oplink->PairSignalStrengthLabel1->setText(QString("%1dB").arg(pairRssiField->getValue(0).toInt()));
|
||||
m_oplink->PairSignalStrengthLabel2->setText(QString("%1dB").arg(pairRssiField->getValue(1).toInt()));
|
||||
m_oplink->PairSignalStrengthLabel3->setText(QString("%1dB").arg(pairRssiField->getValue(2).toInt()));
|
||||
m_oplink->PairSignalStrengthLabel4->setText(QString("%1dB").arg(pairRssiField->getValue(3).toInt()));
|
||||
} else {
|
||||
qDebug() << "PipXtremeGadgetWidget: Count not read PairID field.";
|
||||
}
|
||||
|
||||
@ -208,7 +212,7 @@ void ConfigPipXtremeWidget::updateStatus(UAVObject *object)
|
||||
* 20 bytes: SHA1 sum of the firmware.
|
||||
* 40 bytes: free for now.
|
||||
*/
|
||||
char buf[PipXStatus::DESCRIPTION_NUMELEM];
|
||||
char buf[OPLinkStatus::DESCRIPTION_NUMELEM];
|
||||
for (unsigned int i = 0; i < 26; ++i)
|
||||
buf[i] = descField->getValue(i + 14).toChar().toAscii();
|
||||
buf[26] = '\0';
|
||||
@ -219,7 +223,7 @@ void ConfigPipXtremeWidget::updateStatus(UAVObject *object)
|
||||
gitDate += descField->getValue(11-i).toChar().toAscii() & 0xFF;
|
||||
}
|
||||
QString date = QDateTime::fromTime_t(gitDate).toUTC().toString("yyyy-MM-dd HH:mm");
|
||||
m_pipx->FirmwareVersion->setText(descstr + " " + date);
|
||||
m_oplink->FirmwareVersion->setText(descstr + " " + date);
|
||||
} else {
|
||||
qDebug() << "PipXtremeGadgetWidget: Count not read Description field.";
|
||||
}
|
||||
@ -227,16 +231,16 @@ void ConfigPipXtremeWidget::updateStatus(UAVObject *object)
|
||||
// Update the serial number field
|
||||
UAVObjectField* serialField = object->getField("CPUSerial");
|
||||
if (serialField) {
|
||||
char buf[PipXStatus::CPUSERIAL_NUMELEM * 2 + 1];
|
||||
for (unsigned int i = 0; i < PipXStatus::CPUSERIAL_NUMELEM; ++i)
|
||||
char buf[OPLinkStatus::CPUSERIAL_NUMELEM * 2 + 1];
|
||||
for (unsigned int i = 0; i < OPLinkStatus::CPUSERIAL_NUMELEM; ++i)
|
||||
{
|
||||
unsigned char val = serialField->getValue(i).toUInt() >> 4;
|
||||
buf[i * 2] = ((val < 10) ? '0' : '7') + val;
|
||||
val = serialField->getValue(i).toUInt() & 0xf;
|
||||
buf[i * 2 + 1] = ((val < 10) ? '0' : '7') + val;
|
||||
}
|
||||
buf[PipXStatus::CPUSERIAL_NUMELEM * 2] = '\0';
|
||||
m_pipx->SerialNumber->setText(buf);
|
||||
buf[OPLinkStatus::CPUSERIAL_NUMELEM * 2] = '\0';
|
||||
m_oplink->SerialNumber->setText(buf);
|
||||
} else {
|
||||
qDebug() << "PipXtremeGadgetWidget: Count not read Description field.";
|
||||
}
|
||||
@ -244,35 +248,35 @@ void ConfigPipXtremeWidget::updateStatus(UAVObject *object)
|
||||
// Update the DeviceID field
|
||||
UAVObjectField* idField = object->getField("DeviceID");
|
||||
if (idField) {
|
||||
m_pipx->DeviceID->setText(QString::number(idField->getValue().toUInt(), 16).toUpper());
|
||||
m_oplink->DeviceID->setText(QString::number(idField->getValue().toUInt(), 16).toUpper());
|
||||
} else {
|
||||
qDebug() << "PipXtremeGadgetWidget: Count not read DeviceID field.";
|
||||
}
|
||||
|
||||
// Update the PairID field
|
||||
m_pipx->PairID->setText(QString::number(pairID, 16).toUpper());
|
||||
m_oplink->PairID->setText(QString::number(pairID, 16).toUpper());
|
||||
|
||||
// Update the link state
|
||||
UAVObjectField* linkField = object->getField("LinkState");
|
||||
if (linkField) {
|
||||
m_pipx->LinkState->setText(linkField->getValue().toString());
|
||||
m_oplink->LinkState->setText(linkField->getValue().toString());
|
||||
} else {
|
||||
qDebug() << "PipXtremeGadgetWidget: Count not read link state field.";
|
||||
}
|
||||
}
|
||||
|
||||
/*!
|
||||
\brief Called by updates to @PipXSettings
|
||||
\brief Called by updates to @OPLinkSettings
|
||||
*/
|
||||
void ConfigPipXtremeWidget::updateSettings(UAVObject *object)
|
||||
{
|
||||
Q_UNUSED(object);
|
||||
|
||||
if (!settingsUpdated)
|
||||
{
|
||||
settingsUpdated = true;
|
||||
enableControls(true);
|
||||
}
|
||||
{
|
||||
settingsUpdated = true;
|
||||
enableControls(true);
|
||||
}
|
||||
}
|
||||
|
||||
void ConfigPipXtremeWidget::disconnected()
|
||||
@ -288,20 +292,20 @@ void ConfigPipXtremeWidget::pairIDToggled(bool checked, quint8 idx)
|
||||
{
|
||||
if(checked)
|
||||
{
|
||||
PipXStatus *pipxStatus = PipXStatus::GetInstance(getObjectManager());
|
||||
PipXSettings *pipxSettings = PipXSettings::GetInstance(getObjectManager());
|
||||
OPLinkStatus *oplinkStatus = OPLinkStatus::GetInstance(getObjectManager());
|
||||
OPLinkSettings *oplinkSettings = OPLinkSettings::GetInstance(getObjectManager());
|
||||
|
||||
if (pipxStatus && pipxSettings)
|
||||
if (oplinkStatus && oplinkSettings)
|
||||
{
|
||||
if (idx == 4)
|
||||
{
|
||||
pipxSettings->setPairID(0);
|
||||
oplinkSettings->setPairID(0);
|
||||
}
|
||||
else
|
||||
{
|
||||
quint32 pairID = pipxStatus->getPairIDs(idx);
|
||||
quint32 pairID = oplinkStatus->getPairIDs(idx);
|
||||
if (pairID)
|
||||
pipxSettings->setPairID(pairID);
|
||||
oplinkSettings->setPairID(pairID);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
@ -43,13 +43,13 @@ public slots:
|
||||
void updateSettings(UAVObject *object1);
|
||||
|
||||
private:
|
||||
Ui_PipXtremeWidget *m_pipx;
|
||||
Ui_PipXtremeWidget *m_oplink;
|
||||
|
||||
// The PipXtreme status UAVObject
|
||||
UAVDataObject* pipxStatusObj;
|
||||
// The OPLink status UAVObject
|
||||
UAVDataObject* oplinkStatusObj;
|
||||
|
||||
// The PipXtreme ssettins UAVObject
|
||||
UAVDataObject* pipxSettingsObj;
|
||||
// The OPLink ssettins UAVObject
|
||||
UAVDataObject* oplinkSettingsObj;
|
||||
|
||||
bool settingsUpdated;
|
||||
|
||||
|
@ -111,6 +111,7 @@ void inputChannelForm::groupUpdated()
|
||||
count = 8; // Need to make this 6 for CC
|
||||
break;
|
||||
case ManualControlSettings::CHANNELGROUPS_PPM:
|
||||
case ManualControlSettings::CHANNELGROUPS_OPLINK:
|
||||
case ManualControlSettings::CHANNELGROUPS_DSMMAINPORT:
|
||||
case ManualControlSettings::CHANNELGROUPS_DSMFLEXIPORT:
|
||||
count = 12;
|
||||
|
@ -434,7 +434,7 @@
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="0">
|
||||
<item row="1" column="0">
|
||||
<widget class="QLabel" name="label_2">
|
||||
<property name="text">
|
||||
<string>Serial Number</string>
|
||||
@ -444,7 +444,7 @@
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="1" colspan="3">
|
||||
<item row="1" column="1" colspan="3">
|
||||
<widget class="QLineEdit" name="SerialNumber">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
|
||||
@ -498,7 +498,7 @@
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="0">
|
||||
<item row="2" column="0">
|
||||
<widget class="QLabel" name="DeviceIDLabel">
|
||||
<property name="text">
|
||||
<string>Device ID</string>
|
||||
@ -508,7 +508,7 @@
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="1">
|
||||
<item row="2" column="1">
|
||||
<widget class="QLineEdit" name="DeviceID">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
@ -552,7 +552,7 @@
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="2">
|
||||
<item row="3" column="0">
|
||||
<widget class="QLabel" name="PairIDLabel">
|
||||
<property name="text">
|
||||
<string>Pair ID</string>
|
||||
@ -562,7 +562,7 @@
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="3">
|
||||
<item row="3" column="1">
|
||||
<widget class="QLineEdit" name="PairID">
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
@ -601,9 +601,9 @@
|
||||
</widget>
|
||||
</item>
|
||||
<item row="4" column="0">
|
||||
<widget class="QLabel" name="label_3">
|
||||
<widget class="QLabel" name="label_11">
|
||||
<property name="text">
|
||||
<string>Min Frequency</string>
|
||||
<string>Link State</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
@ -611,9 +611,9 @@
|
||||
</widget>
|
||||
</item>
|
||||
<item row="4" column="1">
|
||||
<widget class="QLineEdit" name="MinFrequency">
|
||||
<widget class="QLineEdit" name="LinkState">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
|
||||
<sizepolicy hsizetype="Expanding" vsizetype="Fixed">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
@ -637,13 +637,13 @@
|
||||
</font>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>The modems minimum allowed frequency</string>
|
||||
<string>The modems current state</string>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">QLineEdit {
|
||||
border: none;
|
||||
border-radius: 1px;
|
||||
padding: 0 4px;
|
||||
padding: 0 3px;
|
||||
background: rgba(0, 0, 0, 16);
|
||||
/* background: transparent; */
|
||||
/* selection-background-color: darkgray;*/
|
||||
@ -655,63 +655,15 @@
|
||||
<property name="readOnly">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="4" column="2">
|
||||
<widget class="QLabel" name="label_4">
|
||||
<property name="text">
|
||||
<string>Max Frequency</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="4" column="3">
|
||||
<widget class="QLineEdit" name="MaxFrequency">
|
||||
<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 modems maximum allowed frequency</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 name="placeholderText">
|
||||
<string>Disconnected</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="5" column="0">
|
||||
<widget class="QLabel" name="label_12">
|
||||
<widget class="QLabel" name="LinkQualityLabel">
|
||||
<property name="text">
|
||||
<string>Freq. Step Size</string>
|
||||
<string>Link Quality</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
@ -719,19 +671,7 @@
|
||||
</widget>
|
||||
</item>
|
||||
<item row="5" column="1">
|
||||
<widget class="QLineEdit" name="FrequencyStepSize">
|
||||
<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>
|
||||
<widget class="QLineEdit" name="LinkQuality">
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>101</width>
|
||||
@ -744,9 +684,6 @@
|
||||
<bold>true</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>The modems minimum frequency step size</string>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">QLineEdit {
|
||||
border: none;
|
||||
@ -757,59 +694,8 @@
|
||||
/* 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="FreqBandLabel">
|
||||
<property name="text">
|
||||
<string>Freq. Band</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="5" column="3">
|
||||
<widget class="QLineEdit" name="FreqBand">
|
||||
<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 current frequency band</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 name="frame">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="readOnly">
|
||||
<bool>true</bool>
|
||||
@ -861,18 +747,18 @@
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="6" column="2">
|
||||
<item row="7" column="0">
|
||||
<widget class="QLabel" name="RxAFCLabel">
|
||||
<property name="text">
|
||||
<string>Rx AFC</string>
|
||||
<string>AFC Corr.</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="6" column="3">
|
||||
<widget class="QLineEdit" name="RxAFC">
|
||||
<item row="7" column="1">
|
||||
<widget class="QLineEdit" name="AFCCorrection">
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>101</width>
|
||||
@ -900,7 +786,55 @@
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="7" column="0">
|
||||
<item row="8" column="0">
|
||||
<widget class="QLabel" name="TXSeqLabel">
|
||||
<property name="text">
|
||||
<string>TX Seq. No.</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="8" column="1">
|
||||
<widget class="QLineEdit" name="TXSeq">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>101</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>75</weight>
|
||||
<bold>true</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">QLineEdit {
|
||||
border: none;
|
||||
border-radius: 1px;
|
||||
padding: 0 4px;
|
||||
background: rgba(0, 0, 0, 16);
|
||||
/* background: transparent; */
|
||||
/* selection-background-color: darkgray;*/
|
||||
}</string>
|
||||
</property>
|
||||
<property name="frame">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="readOnly">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="9" column="0">
|
||||
<widget class="QLabel" name="TXRateLabel">
|
||||
<property name="text">
|
||||
<string>TX Rate (B/s)</string>
|
||||
@ -910,7 +844,7 @@
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="7" column="1">
|
||||
<item row="9" column="1">
|
||||
<widget class="QLineEdit" name="TXRate">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
@ -948,7 +882,55 @@
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="7" column="2">
|
||||
<item row="10" column="0">
|
||||
<widget class="QLabel" name="RXSeqLabel">
|
||||
<property name="text">
|
||||
<string>RX Seq. No.</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="10" column="1">
|
||||
<widget class="QLineEdit" name="RXSeq">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>101</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>75</weight>
|
||||
<bold>true</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">QLineEdit {
|
||||
border: none;
|
||||
border-radius: 1px;
|
||||
padding: 0 4px;
|
||||
background: rgba(0, 0, 0, 16);
|
||||
/* background: transparent; */
|
||||
/* selection-background-color: darkgray;*/
|
||||
}</string>
|
||||
</property>
|
||||
<property name="frame">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="readOnly">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="11" column="0">
|
||||
<widget class="QLabel" name="RXRateLabel">
|
||||
<property name="text">
|
||||
<string>RX Rate (B/s)</string>
|
||||
@ -958,7 +940,7 @@
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="7" column="3">
|
||||
<item row="11" column="1">
|
||||
<widget class="QLineEdit" name="RXRate">
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
@ -990,20 +972,20 @@
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="8" column="0">
|
||||
<widget class="QLabel" name="label_11">
|
||||
<item row="2" column="2">
|
||||
<widget class="QLabel" name="GoodLabel">
|
||||
<property name="text">
|
||||
<string>Link State</string>
|
||||
<string>RX Good</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="8" column="1">
|
||||
<widget class="QLineEdit" name="LinkState">
|
||||
<item row="2" column="3">
|
||||
<widget class="QLineEdit" name="Good">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Expanding" vsizetype="Fixed">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
@ -1027,52 +1009,7 @@
|
||||
</font>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>The modems current state</string>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">QLineEdit {
|
||||
border: none;
|
||||
border-radius: 1px;
|
||||
padding: 0 3px;
|
||||
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>
|
||||
<property name="placeholderText">
|
||||
<string>Disconnected</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="8" column="2">
|
||||
<widget class="QLabel" name="LinkQualityLabel">
|
||||
<property name="text">
|
||||
<string>Link Quality</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="8" column="3">
|
||||
<widget class="QLineEdit" name="LinkQuality">
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>101</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>75</weight>
|
||||
<bold>true</bold>
|
||||
</font>
|
||||
<string>The percentage of packets that were corrected with error correction</string>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">QLineEdit {
|
||||
@ -1084,32 +1021,350 @@
|
||||
/* selection-background-color: darkgray;*/
|
||||
}</string>
|
||||
</property>
|
||||
<property name="frame">
|
||||
<bool>false</bool>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
<property name="readOnly">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="9" column="0">
|
||||
<widget class="QLabel" name="RetriesLabel">
|
||||
<item row="3" column="2">
|
||||
<widget class="QLabel" name="CorrectedLabel">
|
||||
<property name="text">
|
||||
<string>Retries</string>
|
||||
<string>RX Corrected</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="9" column="1">
|
||||
<widget class="QLineEdit" name="Retries">
|
||||
<item row="3" column="3">
|
||||
<widget class="QLineEdit" name="Corrected">
|
||||
<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>101</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>75</weight>
|
||||
<bold>true</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>The percentage of packets that were corrected with error correction</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="4" column="2">
|
||||
<widget class="QLabel" name="ErrorsLabel">
|
||||
<property name="text">
|
||||
<string>RX Errors</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="4" column="3">
|
||||
<widget class="QLineEdit" name="Errors">
|
||||
<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 percentage of packets that could not be corrected with error correction</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="MissedPacketsLabel">
|
||||
<property name="text">
|
||||
<string>RX Missed</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="5" column="3">
|
||||
<widget class="QLineEdit" name="Missed">
|
||||
<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>101</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>75</weight>
|
||||
<bold>true</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>The percentage of packets that were not received at all</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="6" column="2">
|
||||
<widget class="QLabel" name="RxFailureLabel">
|
||||
<property name="text">
|
||||
<string>RX Failure</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="6" column="3">
|
||||
<widget class="QLineEdit" name="RxFailure">
|
||||
<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>101</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>75</weight>
|
||||
<bold>true</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>The percentage of packets that were not received at all</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="7" column="2">
|
||||
<widget class="QLabel" name="DroppedLabel">
|
||||
<property name="text">
|
||||
<string>TX Dropped</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="7" column="3">
|
||||
<widget class="QLineEdit" name="Dropped">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>101</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>75</weight>
|
||||
<bold>true</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>The number of packets that were unable to be transmitted</string>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">QLineEdit {
|
||||
border: none;
|
||||
border-radius: 1px;
|
||||
padding: 0 4px;
|
||||
background: rgba(0, 0, 0, 16);
|
||||
/* background: transparent; */
|
||||
/* selection-background-color: darkgray;*/
|
||||
}</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
<property name="readOnly">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="8" column="2">
|
||||
<widget class="QLabel" name="ResentLabel">
|
||||
<property name="text">
|
||||
<string>TX Resent</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="8" column="3">
|
||||
<widget class="QLineEdit" name="Resent">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>101</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>75</weight>
|
||||
<bold>true</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>The number of packets that were unable to be transmitted</string>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">QLineEdit {
|
||||
border: none;
|
||||
border-radius: 1px;
|
||||
padding: 0 4px;
|
||||
background: rgba(0, 0, 0, 16);
|
||||
/* background: transparent; */
|
||||
/* selection-background-color: darkgray;*/
|
||||
}</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
<property name="readOnly">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="9" column="2">
|
||||
<widget class="QLabel" name="TxFailureLabel">
|
||||
<property name="text">
|
||||
<string>Tx Failure</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="9" column="3">
|
||||
<widget class="QLineEdit" name="TxFailure">
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>101</width>
|
||||
@ -1140,7 +1395,7 @@
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="9" column="2">
|
||||
<item row="10" column="2">
|
||||
<widget class="QLabel" name="UAVTalkErrorsLabel">
|
||||
<property name="text">
|
||||
<string>UAVTalk Errors</string>
|
||||
@ -1150,7 +1405,7 @@
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="9" column="3">
|
||||
<item row="10" column="3">
|
||||
<widget class="QLineEdit" name="UAVTalkErrors">
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
@ -1182,7 +1437,7 @@
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="10" column="0">
|
||||
<item row="11" column="2">
|
||||
<widget class="QLabel" name="ResetsLabel">
|
||||
<property name="text">
|
||||
<string>Resets</string>
|
||||
@ -1192,7 +1447,7 @@
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="10" column="1">
|
||||
<item row="11" column="3">
|
||||
<widget class="QLineEdit" name="Resets">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
@ -1230,18 +1485,18 @@
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="10" column="2">
|
||||
<widget class="QLabel" name="DroppedLabel">
|
||||
<item row="12" column="2">
|
||||
<widget class="QLabel" name="TimeoutsLabel">
|
||||
<property name="text">
|
||||
<string>Dropped</string>
|
||||
<string>Timeouts</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="10" column="3">
|
||||
<widget class="QLineEdit" name="Dropped">
|
||||
<item row="12" column="3">
|
||||
<widget class="QLineEdit" name="Timeouts">
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>101</width>
|
||||
@ -1296,18 +1551,39 @@
|
||||
<string>Configuration</string>
|
||||
</property>
|
||||
<layout class="QGridLayout" name="gridLayout_2">
|
||||
<item row="0" column="0">
|
||||
<widget class="QLabel" name="TelemPortConfigLabel">
|
||||
<item row="0" column="1">
|
||||
<widget class="QCheckBox" name="Coordinator">
|
||||
<property name="text">
|
||||
<string>Coordinator</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="1">
|
||||
<widget class="QCheckBox" name="PPM">
|
||||
<property name="text">
|
||||
<string>PPM</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="1">
|
||||
<widget class="QCheckBox" name="UAVTalk">
|
||||
<property name="text">
|
||||
<string>UAVTalk</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="0">
|
||||
<widget class="QLabel" name="InputConnectionLabel">
|
||||
<property name="text">
|
||||
<string>Telemetry Port Config.</string>
|
||||
<string>Input Connection</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="TelemPortConfig">
|
||||
<item row="3" column="1">
|
||||
<widget class="QComboBox" name="InputConnection">
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>16777215</width>
|
||||
@ -1315,22 +1591,45 @@
|
||||
</size>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Set the telemetry port configuration</string>
|
||||
<string>Choose which port to communicate over on this modem</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="0">
|
||||
<widget class="QLabel" name="TelemPortSpeedLabel">
|
||||
<item row="4" column="0">
|
||||
<widget class="QLabel" name="OutputConnectionLabel">
|
||||
<property name="text">
|
||||
<string>Telemetry Port Speed</string>
|
||||
<string>Output Connection</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="1">
|
||||
<widget class="QComboBox" name="TelemPortSpeed">
|
||||
<item row="4" column="1">
|
||||
<widget class="QComboBox" name="OutputConnection">
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>16777215</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Choose which port to communicate over on the remote modem</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="5" column="0">
|
||||
<widget class="QLabel" name="ComSpeedLabel">
|
||||
<property name="text">
|
||||
<string>COM Speed</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="5" column="1">
|
||||
<widget class="QComboBox" name="ComSpeed">
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>16777215</width>
|
||||
@ -1342,122 +1641,7 @@
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="0">
|
||||
<widget class="QLabel" name="FlexiPortConfigLabel">
|
||||
<property name="text">
|
||||
<string>Flexi Port Configuration</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="FlexiPortConfig">
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>16777215</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Set the flexi port configuration</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="0">
|
||||
<widget class="QLabel" name="FlexiPortSpeedConfig">
|
||||
<property name="text">
|
||||
<string>Flexi Port Speed</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="1">
|
||||
<widget class="QComboBox" name="FlexiPortSpeed">
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>16777215</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Set the flexi port speed</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="4" column="0">
|
||||
<widget class="QLabel" name="VCPConfigLabel">
|
||||
<property name="text">
|
||||
<string>VCP Configuration</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="4" column="1">
|
||||
<widget class="QComboBox" name="VCPConfig">
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>16777215</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Set the virtual serial port configuration</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="5" column="0">
|
||||
<widget class="QLabel" name="VCPSpeedLabel">
|
||||
<property name="text">
|
||||
<string>VCP Speed</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="5" column="1">
|
||||
<widget class="QComboBox" name="VCPSpeed">
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>16777215</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Set the virtual serial port speed</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="6" column="0">
|
||||
<widget class="QLabel" name="MaxRFDatarateLabel">
|
||||
<property name="text">
|
||||
<string>Max RF Datarate (bits/s)</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="6" column="1">
|
||||
<widget class="QComboBox" name="MaxRFDatarate">
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>16777215</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Set the maximum RF datarate/channel bandwidth the modem will use</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="7" column="0">
|
||||
<widget class="QLabel" name="MaxRFTxPowerLabel">
|
||||
<property name="text">
|
||||
<string>Max RF Tx Power(mW)</string>
|
||||
@ -1467,7 +1651,7 @@
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="7" column="1">
|
||||
<item row="6" column="1">
|
||||
<widget class="QComboBox" name="MaxRFTxPower">
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
@ -1486,7 +1670,7 @@
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="8" column="0">
|
||||
<item row="7" column="0">
|
||||
<widget class="QLabel" name="SendTimeoutLabel">
|
||||
<property name="text">
|
||||
<string>Send Timeout (ms)</string>
|
||||
@ -1496,7 +1680,7 @@
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="8" column="1">
|
||||
<item row="7" column="1">
|
||||
<widget class="QSpinBox" name="SendTimeout">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
|
||||
@ -1511,7 +1695,7 @@
|
||||
</size>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Calibrate the modems RF carrier frequency</string>
|
||||
<string>Set the send timeout</string>
|
||||
</property>
|
||||
<property name="accelerated">
|
||||
<bool>true</bool>
|
||||
@ -1521,7 +1705,7 @@
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="9" column="0">
|
||||
<item row="8" column="0">
|
||||
<widget class="QLabel" name="MinPacketSizeLabel">
|
||||
<property name="text">
|
||||
<string>Min Packet Size</string>
|
||||
@ -1531,7 +1715,7 @@
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="9" column="1">
|
||||
<item row="8" column="1">
|
||||
<widget class="QSpinBox" name="MinPacketSize">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
|
||||
@ -1546,7 +1730,7 @@
|
||||
</size>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Calibrate the modems RF carrier frequency</string>
|
||||
<string>Set the minimum packet size</string>
|
||||
</property>
|
||||
<property name="accelerated">
|
||||
<bool>true</bool>
|
||||
@ -1556,7 +1740,7 @@
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="10" column="0">
|
||||
<item row="9" column="0">
|
||||
<widget class="QLabel" name="FreqCalLabel">
|
||||
<property name="text">
|
||||
<string>Frequency Calibration</string>
|
||||
@ -1566,7 +1750,7 @@
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="10" column="1">
|
||||
<item row="9" column="1">
|
||||
<widget class="QSpinBox" name="FrequencyCalibration">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
|
||||
@ -1591,18 +1775,18 @@
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="11" column="0">
|
||||
<item row="10" column="0">
|
||||
<widget class="QLabel" name="label_5">
|
||||
<property name="text">
|
||||
<string>Frequency (Hz)</string>
|
||||
<string>Min. Frequency (Hz)</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="11" column="1">
|
||||
<widget class="QSpinBox" name="Frequency">
|
||||
<item row="10" column="1">
|
||||
<widget class="QSpinBox" name="MinFrequency">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
|
||||
<horstretch>0</horstretch>
|
||||
@ -1616,7 +1800,7 @@
|
||||
</size>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Set the modems RF carrier frequency</string>
|
||||
<string>Set the modems minimum RF carrier frequency</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter</set>
|
||||
@ -1625,7 +1809,7 @@
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="minimum">
|
||||
<number>0</number>
|
||||
<number>400000000</number>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<number>1000000000</number>
|
||||
@ -1635,7 +1819,51 @@
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="15" column="0" colspan="2">
|
||||
<item row="11" column="0">
|
||||
<widget class="QLabel" name="MaxFrequencyLabel">
|
||||
<property name="text">
|
||||
<string>Max. Frequency (Hz)</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="11" column="1">
|
||||
<widget class="QSpinBox" name="MaxFrequency">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>16777215</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Set the modems maximum RF carrier frequency</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
<property name="accelerated">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="minimum">
|
||||
<number>400000000</number>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<number>1000000000</number>
|
||||
</property>
|
||||
<property name="singleStep">
|
||||
<number>100000</number>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="12" column="0" colspan="2">
|
||||
<widget class="QGroupBox" name="groupBox_4">
|
||||
<property name="title">
|
||||
<string>AES Encryption</string>
|
||||
@ -1704,7 +1932,7 @@
|
||||
</layout>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="16" column="0">
|
||||
<item row="13" column="0">
|
||||
<spacer name="verticalSpacer">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Vertical</enum>
|
||||
@ -1717,16 +1945,6 @@
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
<item row="14" column="0" colspan="2">
|
||||
<widget class="QPushButton" name="ScanSpectrum">
|
||||
<property name="toolTip">
|
||||
<string>Scan whole band to see where their is interference and/or used channels</string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string> Scan Spectrum </string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
</item>
|
||||
@ -1747,9 +1965,6 @@
|
||||
<tabstop>FirmwareVersion</tabstop>
|
||||
<tabstop>SerialNumber</tabstop>
|
||||
<tabstop>DeviceID</tabstop>
|
||||
<tabstop>MinFrequency</tabstop>
|
||||
<tabstop>MaxFrequency</tabstop>
|
||||
<tabstop>FrequencyStepSize</tabstop>
|
||||
<tabstop>LinkState</tabstop>
|
||||
<tabstop>RxAFC</tabstop>
|
||||
<tabstop>Retries</tabstop>
|
||||
|
@ -95,8 +95,8 @@ HEADERS += $$UAVOBJECT_SYNTHETICS/accessorydesired.h \
|
||||
$$UAVOBJECT_SYNTHETICS/txpidsettings.h \
|
||||
$$UAVOBJECT_SYNTHETICS/cameradesired.h \
|
||||
$$UAVOBJECT_SYNTHETICS/faultsettings.h \
|
||||
$$UAVOBJECT_SYNTHETICS/pipxsettings.h \
|
||||
$$UAVOBJECT_SYNTHETICS/pipxstatus.h \
|
||||
$$UAVOBJECT_SYNTHETICS/oplinksettings.h \
|
||||
$$UAVOBJECT_SYNTHETICS/oplinkstatus.h \
|
||||
$$UAVOBJECT_SYNTHETICS/osdsettings.h \
|
||||
$$UAVOBJECT_SYNTHETICS/waypoint.h \
|
||||
$$UAVOBJECT_SYNTHETICS/waypointactive.h
|
||||
@ -174,8 +174,8 @@ SOURCES += $$UAVOBJECT_SYNTHETICS/accessorydesired.cpp \
|
||||
$$UAVOBJECT_SYNTHETICS/txpidsettings.cpp \
|
||||
$$UAVOBJECT_SYNTHETICS/cameradesired.cpp \
|
||||
$$UAVOBJECT_SYNTHETICS/faultsettings.cpp \
|
||||
$$UAVOBJECT_SYNTHETICS/pipxsettings.cpp \
|
||||
$$UAVOBJECT_SYNTHETICS/pipxstatus.cpp \
|
||||
$$UAVOBJECT_SYNTHETICS/oplinksettings.cpp \
|
||||
$$UAVOBJECT_SYNTHETICS/oplinkstatus.cpp \
|
||||
$$UAVOBJECT_SYNTHETICS/osdsettings.cpp \
|
||||
$$UAVOBJECT_SYNTHETICS/waypoint.cpp \
|
||||
$$UAVOBJECT_SYNTHETICS/waypointactive.cpp
|
||||
|
@ -27,7 +27,7 @@
|
||||
|
||||
#include "telemetry.h"
|
||||
#include "qxtlogger.h"
|
||||
#include "pipxsettings.h"
|
||||
#include "oplinksettings.h"
|
||||
#include "objectpersistence.h"
|
||||
#include <QTime>
|
||||
#include <QtGlobal>
|
||||
@ -376,7 +376,7 @@ void Telemetry::processObjectQueue()
|
||||
if ( gcsStats.Status != GCSTelemetryStats::STATUS_CONNECTED )
|
||||
{
|
||||
objQueue.clear();
|
||||
if ( objInfo.obj->getObjID() != GCSTelemetryStats::OBJID && objInfo.obj->getObjID() != PipXSettings::OBJID && objInfo.obj->getObjID() != ObjectPersistence::OBJID )
|
||||
if ( objInfo.obj->getObjID() != GCSTelemetryStats::OBJID && objInfo.obj->getObjID() != OPLinkSettings::OBJID && objInfo.obj->getObjID() != ObjectPersistence::OBJID )
|
||||
{
|
||||
objInfo.obj->emitTransactionCompleted(false);
|
||||
return;
|
||||
|
@ -15,6 +15,8 @@
|
||||
<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" defaultvalue="Telemetry"/>
|
||||
<field name="RM_FlexiPort" units="function" type="enum" elements="1" options="Disabled,Telemetry,GPS,I2C,DSM2,DSMX (10bit),DSMX (11bit),DebugConsole,ComBridge" defaultvalue="Disabled"/>
|
||||
|
||||
<field name="RadioPort" units="function" type="enum" elements="1" options="Disabled,Telemetry" defaultvalue="Disabled"/>
|
||||
|
||||
<field name="TelemetrySpeed" units="bps" type="enum" elements="1" options="2400,4800,9600,19200,38400,57600,115200" defaultvalue="57600"/>
|
||||
<field name="GPSSpeed" units="bps" type="enum" elements="1" options="2400,4800,9600,19200,38400,57600,115200" defaultvalue="57600"/>
|
||||
@ -22,7 +24,7 @@
|
||||
<field name="USB_HIDPort" units="function" type="enum" elements="1" options="USBTelemetry,RCTransmitter,Disabled" defaultvalue="USBTelemetry"/>
|
||||
<field name="USB_VCPPort" units="function" type="enum" elements="1" options="USBTelemetry,ComBridge,DebugConsole,Disabled" defaultvalue="Disabled"/>
|
||||
|
||||
<field name="OptionalModules" units="" type="enum" elementnames="CameraStab,GPS,ComUsbBridge,Fault,Altitude,Airspeed,TxPID,Autotune,VtolPathFollower,FixedWingPathFollower,Battery,Overo,Radio" options="Disabled,Enabled" defaultvalue="Disabled"/>
|
||||
<field name="OptionalModules" units="" type="enum" elementnames="CameraStab,GPS,ComUsbBridge,Fault,Altitude,Airspeed,TxPID,Autotune,VtolPathFollower,FixedWingPathFollower,Battery,Overo" options="Disabled,Enabled" defaultvalue="Disabled"/>
|
||||
<field name="ADCRouting" units="" type="enum" elementnames="ADC0,ADC1,ADC2,ADC3" options="Disabled,BatteryVoltage,BatteryCurrent,AnalogAirspeed,Generic" defaultvalue="Disabled"/>
|
||||
<field name="DSMxBind" units="" type="uint8" elements="1" defaultvalue="0"/>
|
||||
|
||||
|
@ -3,7 +3,7 @@
|
||||
<description>Settings to indicate how to decode receiver input by @ref ManualControlModule.</description>
|
||||
<field name="ChannelGroups" units="Channel Group" type="enum"
|
||||
elementnames="Throttle,Roll,Pitch,Yaw,FlightMode,Collective,Accessory0,Accessory1,Accessory2"
|
||||
options="PWM,PPM,DSM (MainPort),DSM (FlexiPort),S.Bus,GCS,None" defaultvalue="None"/>
|
||||
options="PWM,PPM,DSM (MainPort),DSM (FlexiPort),S.Bus,GCS,OPLink,None" defaultvalue="None"/>
|
||||
<field name="ChannelNumber" units="channel" type="uint8" defaultvalue="0"
|
||||
elementnames="Throttle,Roll,Pitch,Yaw,FlightMode,Collective,Accessory0,Accessory1,Accessory2"/>
|
||||
<field name="ChannelMin" units="us" type="int16" defaultvalue="1000"
|
||||
|
24
shared/uavobjectdefinition/oplinksettings.xml
Normal file
24
shared/uavobjectdefinition/oplinksettings.xml
Normal file
@ -0,0 +1,24 @@
|
||||
<xml>
|
||||
<object name="OPLinkSettings" singleinstance="true" settings="true">
|
||||
<description>OPLink configurations options.</description>
|
||||
<field name="PairID" units="" type="uint32" elements="1" defaultvalue="0"/>
|
||||
<field name="Coordinator" units="binary" type="enum" elements="1" options="FALSE,TRUE" defaultvalue="FALSE"/>
|
||||
<field name="PPM" units="binary" type="enum" elements="1" options="FALSE,TRUE" defaultvalue="FALSE"/>
|
||||
<field name="UAVTalk" units="binary" type="enum" elements="1" options="FALSE,TRUE" defaultvalue="FALSE"/>
|
||||
<field name="InputConnection" units="function" type="enum" elements="1" options="HID,VCP,Telemetry,Flexi" defaultvalue="HID"/>
|
||||
<field name="OutputConnection" units="function" type="enum" elements="1" options="RemoteHID,RemoteVCP,RemoteTelemetry,RemoteFlexi,Telemetry,Flexi" defaultvalue="RemoteTelemetry"/>
|
||||
<field name="ComSpeed" units="bps" type="enum" elements="1" options="2400,4800,9600,19200,38400,57600,115200" defaultvalue="38400"/>
|
||||
<field name="MaxRFPower" units="mW" type="enum" elements="1" options="1.25,1.6,3.16,6.3,12.6,25,50,100" defaultvalue="100"/>
|
||||
<field name="SendTimeout" units="ms" type="uint16" elements="1" defaultvalue="50"/>
|
||||
<field name="MinPacketSize" units="bytes" type="uint8" elements="1" defaultvalue="50"/>
|
||||
<field name="FrequencyCalibration" units="" type="uint8" elements="1" defaultvalue="127"/>
|
||||
<field name="MinFrequency" units="" type="uint32" elements="1" defaultvalue="432000000"/>
|
||||
<field name="MaxFrequency" units="" type="uint32" elements="1" defaultvalue="436000000"/>
|
||||
<field name="AESKey" units="" type="uint8" elements="32" defaultvalue="0123456789abcdef0123456789abcdef"/>
|
||||
|
||||
<access gcs="readwrite" flight="readwrite"/>
|
||||
<telemetrygcs acked="true" updatemode="onchange" period="0"/>
|
||||
<telemetryflight acked="true" updatemode="onchange" period="0"/>
|
||||
<logging updatemode="manual" period="0"/>
|
||||
</object>
|
||||
</xml>
|
@ -1,23 +1,29 @@
|
||||
<xml>
|
||||
<object name="PipXStatus" singleinstance="true" settings="false">
|
||||
<description>PipXtreme device status.</description>
|
||||
<object name="OPLinkStatus" singleinstance="true" settings="false">
|
||||
<description>OPLink device status.</description>
|
||||
<field name="Description" units="" type="uint8" elements="40"/>
|
||||
<field name="CPUSerial" units="" type="uint8" elements="12" />
|
||||
<field name="BoardRevision" units="" type="uint16" elements="1"/>
|
||||
<field name="BoardType" units="" type="uint8" elements="1"/>
|
||||
<field name="MinFrequency" units="Hz" type="uint32" elements="1" defaultvalue="0"/>
|
||||
<field name="MaxFrequency" units="Hz" type="uint32" elements="1" defaultvalue="0"/>
|
||||
<field name="FrequencyBand" units="" type="uint8" elements="1" defaultvalue="0"/>
|
||||
<field name="FrequencyStepSize" units="" type="float" elements="1" defaultvalue="0"/>
|
||||
<field name="DeviceID" units="" type="uint32" elements="1" defaultvalue="0"/>
|
||||
<field name="Retries" units="" type="uint16" elements="1" defaultvalue="0"/>
|
||||
<field name="RxGood" units="%" type="uint8" elements="1" defaultvalue="0"/>
|
||||
<field name="RxCorrected" units="%" type="uint8" elements="1" defaultvalue="0"/>
|
||||
<field name="RxErrors" units="%" type="uint8" elements="1" defaultvalue="0"/>
|
||||
<field name="RxMissed" units="%" type="uint8" elements="1" defaultvalue="0"/>
|
||||
<field name="RxFailure" units="%" type="uint8" elements="1" defaultvalue="0"/>
|
||||
<field name="UAVTalkErrors" units="" type="uint16" elements="1" defaultvalue="0"/>
|
||||
<field name="Dropped" units="" type="uint16" elements="1" defaultvalue="0"/>
|
||||
<field name="Resets" units="" type="uint16" elements="1" defaultvalue="0"/>
|
||||
<field name="TxResent" units="%" type="uint8" elements="1" defaultvalue="0"/>
|
||||
<field name="TxDropped" units="%" type="uint8" elements="1" defaultvalue="0"/>
|
||||
<field name="TxFailure" units="%" type="uint8" elements="1" defaultvalue="0"/>
|
||||
<field name="Resets" units="" type="uint8" elements="1" defaultvalue="0"/>
|
||||
<field name="Timeouts" units="" type="uint8" elements="1" defaultvalue="0"/>
|
||||
<field name="RSSI" units="dBm" type="int8" elements="1" defaultvalue="0"/>
|
||||
<field name="AFCCorrection" units="Hz" type="int8" elements="1" defaultvalue="0"/>
|
||||
<field name="LinkQuality" units="" type="uint8" elements="1" defaultvalue="0"/>
|
||||
<field name="TXRate" units="Bps" type="uint16" elements="1" defaultvalue="0"/>
|
||||
<field name="RXRate" units="Bps" type="uint16" elements="1" defaultvalue="0"/>
|
||||
<field name="RSSI" units="dBm" type="int8" elements="1" defaultvalue="0"/>
|
||||
<field name="LinkQuality" units="" type="uint8" 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="PairIDs" units="" type="uint32" elements="4" defaultvalue="0"/>
|
||||
<field name="PairSignalStrengths" units="dBm" type="int8" elements="4" defaultvalue="-127"/>
|
@ -1,24 +0,0 @@
|
||||
<xml>
|
||||
<object name="PipXSettings" singleinstance="true" settings="true">
|
||||
<description>PipXtreme configurations options.</description>
|
||||
<field name="PairID" units="" type="uint32" elements="1" defaultvalue="0"/>
|
||||
<field name="TelemetryConfig" units="function" type="enum" elements="1" options="Disabled,Serial,UAVTalk,GCS,Debug" defaultvalue="UAVTalk"/>
|
||||
<field name="TelemetrySpeed" units="bps" type="enum" elements="1" options="2400,4800,9600,19200,38400,57600,115200" defaultvalue="57600"/>
|
||||
<field name="FlexiConfig" units="function" type="enum" elements="1" options="Disabled,Serial,UAVTalk,GCS,PPM_In,PPM_Out,RSSI,Debug" defaultvalue="Disabled"/>
|
||||
<field name="FlexiSpeed" units="bps" type="enum" elements="1" options="2400,4800,9600,19200,38400,57600,115200" defaultvalue="57600"/>
|
||||
<field name="VCPConfig" units="function" type="enum" elements="1" options="Disabled,Serial,Debug" defaultvalue="Disabled"/>
|
||||
<field name="VCPSpeed" units="bps" type="enum" elements="1" options="2400,4800,9600,19200,38400,57600,115200" defaultvalue="57600"/>
|
||||
<field name="RFSpeed" units="bps" type="enum" elements="1" options="2400,4800,9600,19200,38400,57600,115200" defaultvalue="115200"/>
|
||||
<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="SendTimeout" units="ms" type="uint16" elements="1" defaultvalue="50"/>
|
||||
<field name="MinPacketSize" units="bytes" type="uint8" elements="1" defaultvalue="50"/>
|
||||
<field name="FrequencyCalibration" units="" type="uint8" elements="1" defaultvalue="127"/>
|
||||
<field name="Frequency" units="" type="uint32" elements="1" defaultvalue="434000000"/>
|
||||
<field name="AESKey" units="" type="uint8" elements="32" defaultvalue="0123456789abcdef0123456789abcdef"/>
|
||||
|
||||
<access gcs="readwrite" flight="readwrite"/>
|
||||
<telemetrygcs acked="true" updatemode="onchange" period="0"/>
|
||||
<telemetryflight acked="true" updatemode="onchange" period="0"/>
|
||||
<logging updatemode="manual" period="0"/>
|
||||
</object>
|
||||
</xml>
|
@ -2,7 +2,7 @@
|
||||
<object name="ReceiverActivity" singleinstance="true" settings="false">
|
||||
<description>Monitors which receiver channels have been active within the last second.</description>
|
||||
<field name="ActiveGroup" units="Channel Group" type="enum" elements="1"
|
||||
options="PWM,PPM,DSM (MainPort),DSM (FlexiPort),S.Bus,GCS,None"
|
||||
options="PWM,PPM,DSM (MainPort),DSM (FlexiPort),S.Bus,GCS,OPLink,None"
|
||||
defaultvalue="None"/>
|
||||
<field name="ActiveChannel" units="channel" type="uint8" elements="1"
|
||||
defaultvalue="255"/>
|
||||
|
Loading…
Reference in New Issue
Block a user