mirror of
https://bitbucket.org/librepilot/librepilot.git
synced 2025-02-20 10:54:14 +01:00
Merge branch 'basenext' into corvuscorax/new_navigation
Conflicts: ground/openpilotgcs/src/plugins/uavobjects/uavobjects.pro
This commit is contained in:
commit
922b3b7f1e
@ -34,7 +34,7 @@
|
||||
/* Prototype of PIOS_Board_Init() function */
|
||||
extern void PIOS_Board_Init(void);
|
||||
extern void FLASH_Download();
|
||||
void error(void);
|
||||
void error(int);
|
||||
|
||||
/* The ADDRESSES of the _binary_* symbols are the important
|
||||
* data. This is non-intuitive for _binary_size where you
|
||||
@ -51,11 +51,14 @@ int main() {
|
||||
|
||||
PIOS_SYS_Init();
|
||||
PIOS_Board_Init();
|
||||
PIOS_LED_On(PIOS_LED_HEARTBEAT);
|
||||
PIOS_DELAY_WaitmS(3000);
|
||||
PIOS_LED_Off(PIOS_LED_HEARTBEAT);
|
||||
|
||||
/// Self overwrite check
|
||||
uint32_t base_address = SCB->VTOR;
|
||||
if ((0x08000000 + embedded_image_size) > base_address)
|
||||
error();
|
||||
error(PIOS_LED_HEARTBEAT);
|
||||
///
|
||||
|
||||
/*
|
||||
@ -77,7 +80,7 @@ int main() {
|
||||
if ((pios_board_info_blob.magic != new_board_info_blob->magic) ||
|
||||
(pios_board_info_blob.board_type != new_board_info_blob->board_type) ||
|
||||
(pios_board_info_blob.board_rev != new_board_info_blob->board_rev)) {
|
||||
error();
|
||||
error(PIOS_LED_HEARTBEAT);
|
||||
}
|
||||
|
||||
/* Embedded bootloader looks like it's the right one for this HW, proceed... */
|
||||
@ -105,7 +108,7 @@ int main() {
|
||||
}
|
||||
|
||||
if (fail == true)
|
||||
error();
|
||||
error(PIOS_LED_HEARTBEAT);
|
||||
|
||||
|
||||
///
|
||||
@ -113,6 +116,7 @@ int main() {
|
||||
/// Bootloader programing
|
||||
for (uint32_t offset = 0; offset < embedded_image_size/sizeof(uint32_t); ++offset) {
|
||||
bool result = false;
|
||||
PIOS_LED_Toggle(PIOS_LED_HEARTBEAT);
|
||||
for (uint8_t retry = 0; retry < MAX_WRI_RETRYS; ++retry) {
|
||||
if (result == false) {
|
||||
result = (FLASH_ProgramWord(0x08000000 + (offset * 4), embedded_image_start[offset])
|
||||
@ -120,9 +124,15 @@ int main() {
|
||||
}
|
||||
}
|
||||
if (result == false)
|
||||
error();
|
||||
error(PIOS_LED_HEARTBEAT);
|
||||
}
|
||||
///
|
||||
for (uint8_t x = 0; x < 3; ++x) {
|
||||
PIOS_LED_On(PIOS_LED_HEARTBEAT);
|
||||
PIOS_DELAY_WaitmS(1000);
|
||||
PIOS_LED_Off(PIOS_LED_HEARTBEAT);
|
||||
PIOS_DELAY_WaitmS(1000);
|
||||
}
|
||||
|
||||
/// Invalidate the bootloader updater so we won't run
|
||||
/// the update again on the next power cycle.
|
||||
@ -135,7 +145,11 @@ int main() {
|
||||
|
||||
}
|
||||
|
||||
void error(void) {
|
||||
void error(int led) {
|
||||
for (;;) {
|
||||
PIOS_LED_On(led);
|
||||
PIOS_DELAY_WaitmS(500);
|
||||
PIOS_LED_Off(led);
|
||||
PIOS_DELAY_WaitmS(500);
|
||||
}
|
||||
}
|
||||
|
@ -35,6 +35,8 @@
|
||||
#include <pios.h>
|
||||
|
||||
void PIOS_Board_Init(void) {
|
||||
const struct pios_board_info * bdinfo = &pios_board_info_blob;
|
||||
|
||||
/* Enable Prefetch Buffer */
|
||||
FLASH_PrefetchBufferCmd(FLASH_PrefetchBuffer_Enable);
|
||||
|
||||
@ -42,8 +44,15 @@ void PIOS_Board_Init(void) {
|
||||
FLASH_SetLatency(FLASH_Latency_2);
|
||||
|
||||
/* Delay system */
|
||||
PIOS_DELAY_Init();
|
||||
|
||||
PIOS_DELAY_Init();
|
||||
|
||||
/* LEDs */
|
||||
#if defined(PIOS_INCLUDE_LED)
|
||||
const struct pios_led_cfg * led_cfg = PIOS_BOARD_HW_DEFS_GetLedCfg(bdinfo->board_rev);
|
||||
PIOS_Assert(led_cfg);
|
||||
PIOS_LED_Init(led_cfg);
|
||||
#endif /* PIOS_INCLUDE_LED */
|
||||
|
||||
/* Initialize the PiOS library */
|
||||
PIOS_GPIO_Init();
|
||||
}
|
||||
|
@ -62,17 +62,9 @@ void PIOS_Board_Init(void) {
|
||||
const struct pios_board_info * bdinfo = &pios_board_info_blob;
|
||||
|
||||
#if defined(PIOS_INCLUDE_LED)
|
||||
switch(bdinfo->board_rev) {
|
||||
case 0x01: // Revision 1
|
||||
PIOS_LED_Init(&pios_led_cfg_cc);
|
||||
break;
|
||||
case 0x02: // Revision 2
|
||||
GPIO_PinRemapConfig(GPIO_Remap_SWJ_JTAGDisable, ENABLE);
|
||||
PIOS_LED_Init(&pios_led_cfg_cc3d);
|
||||
break;
|
||||
default:
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
const struct pios_led_cfg * led_cfg = PIOS_BOARD_HW_DEFS_GetLedCfg(bdinfo->board_rev);
|
||||
PIOS_Assert(led_cfg);
|
||||
PIOS_LED_Init(led_cfg);
|
||||
#endif /* PIOS_INCLUDE_LED */
|
||||
|
||||
#if defined(PIOS_INCLUDE_USB)
|
||||
@ -84,10 +76,10 @@ void PIOS_Board_Init(void) {
|
||||
|
||||
uint32_t pios_usb_id;
|
||||
switch(bdinfo->board_rev) {
|
||||
case 0x01: // Revision 1
|
||||
case BOARD_REVISION_CC:
|
||||
PIOS_USB_Init(&pios_usb_id, &pios_usb_main_cfg_cc);
|
||||
break;
|
||||
case 0x02: // Revision 2
|
||||
case BOARD_REVISION_CC3D:
|
||||
PIOS_USB_Init(&pios_usb_id, &pios_usb_main_cfg_cc3d);
|
||||
break;
|
||||
default:
|
||||
|
@ -86,6 +86,7 @@ RTOSDIR = $(APPLIBDIR)/FreeRTOS
|
||||
RTOSSRCDIR = $(RTOSDIR)/Source
|
||||
RTOSINCDIR = $(RTOSSRCDIR)/include
|
||||
DOXYGENDIR = ../Doc/Doxygen
|
||||
HWDEFSINC = ../../board_hw_defs/$(BOARD_NAME)
|
||||
|
||||
# List C source files here. (C dependencies are automatically generated.)
|
||||
# use file-extension c for "c-only"-files
|
||||
@ -199,8 +200,7 @@ EXTRAINCDIRS += $(MSDDIR)
|
||||
EXTRAINCDIRS += $(RTOSINCDIR)
|
||||
EXTRAINCDIRS += $(APPLIBDIR)
|
||||
EXTRAINCDIRS += $(RTOSSRCDIR)/portable/GCC/ARM_CM3
|
||||
|
||||
|
||||
EXTRAINCDIRS += $(HWDEFSINC)
|
||||
|
||||
# List any extra directories to look for library files here.
|
||||
# Also add directories where the linker should search for
|
||||
|
@ -23,97 +23,9 @@
|
||||
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
*/
|
||||
|
||||
#include "board_hw_defs.c"
|
||||
#include <pios.h>
|
||||
|
||||
#if defined(PIOS_INCLUDE_LED)
|
||||
|
||||
#include <pios_led_priv.h>
|
||||
static const struct pios_led pios_leds[] = {
|
||||
[PIOS_LED_USB] = {
|
||||
.pin = {
|
||||
.gpio = GPIOA,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_3,
|
||||
.GPIO_Mode = GPIO_Mode_Out_PP,
|
||||
.GPIO_Speed = GPIO_Speed_50MHz,
|
||||
},
|
||||
},
|
||||
},
|
||||
[PIOS_LED_LINK] = {
|
||||
.pin = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_5,
|
||||
.GPIO_Mode = GPIO_Mode_Out_PP,
|
||||
.GPIO_Speed = GPIO_Speed_50MHz,
|
||||
},
|
||||
},
|
||||
},
|
||||
[PIOS_LED_RX] = {
|
||||
.pin = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_6,
|
||||
.GPIO_Mode = GPIO_Mode_Out_PP,
|
||||
.GPIO_Speed = GPIO_Speed_50MHz,
|
||||
},
|
||||
},
|
||||
},
|
||||
[PIOS_LED_TX] = {
|
||||
.pin = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_7,
|
||||
.GPIO_Mode = GPIO_Mode_Out_PP,
|
||||
.GPIO_Speed = GPIO_Speed_50MHz,
|
||||
},
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
static const struct pios_led_cfg pios_led_cfg = {
|
||||
.leds = pios_leds,
|
||||
.num_leds = NELEMENTS(pios_leds),
|
||||
};
|
||||
|
||||
#endif /* PIOS_INCLUDE_LED */
|
||||
|
||||
#if defined(PIOS_INCLUDE_COM_MSG)
|
||||
|
||||
#include <pios_com_msg_priv.h>
|
||||
|
||||
#endif /* PIOS_INCLUDE_COM_MSG */
|
||||
|
||||
#if defined(PIOS_INCLUDE_USB)
|
||||
#include "pios_usb_priv.h"
|
||||
|
||||
static const struct pios_usb_cfg pios_usb_main_cfg = {
|
||||
.irq = {
|
||||
.init = {
|
||||
.NVIC_IRQChannel = USB_LP_CAN1_RX0_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_LOW,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
#include "pios_usb_board_data_priv.h"
|
||||
#include "pios_usb_desc_hid_only_priv.h"
|
||||
|
||||
#endif /* PIOS_INCLUDE_USB */
|
||||
|
||||
#if defined(PIOS_INCLUDE_USB_HID)
|
||||
#include <pios_usb_hid_priv.h>
|
||||
|
||||
const struct pios_usb_hid_cfg pios_usb_hid_cfg = {
|
||||
.data_if = 0,
|
||||
.data_rx_ep = 1,
|
||||
.data_tx_ep = 1,
|
||||
};
|
||||
|
||||
#endif /* PIOS_INCLUDE_USB_HID */
|
||||
|
||||
uint32_t pios_com_telem_usb_id;
|
||||
|
||||
/**
|
||||
@ -139,6 +51,10 @@ void PIOS_Board_Init(void) {
|
||||
/* Initialize the PiOS library */
|
||||
PIOS_GPIO_Init();
|
||||
|
||||
#if defined(PIOS_INCLUDE_LED)
|
||||
PIOS_LED_Init(&pios_led_cfg);
|
||||
#endif /* PIOS_INCLUDE_LED */
|
||||
|
||||
#if defined(PIOS_INCLUDE_USB)
|
||||
/* Initialize board specific USB data */
|
||||
PIOS_USB_BOARD_DATA_Init();
|
||||
|
@ -156,29 +156,21 @@ void PIOS_Board_Init(void) {
|
||||
const struct pios_board_info * bdinfo = &pios_board_info_blob;
|
||||
|
||||
#if defined(PIOS_INCLUDE_LED)
|
||||
switch(bdinfo->board_rev) {
|
||||
case 0x01: // Revision 1
|
||||
PIOS_LED_Init(&pios_led_cfg_cc);
|
||||
break;
|
||||
case 0x02: // Revision 2
|
||||
GPIO_PinRemapConfig(GPIO_Remap_SWJ_JTAGDisable, ENABLE);
|
||||
PIOS_LED_Init(&pios_led_cfg_cc3d);
|
||||
break;
|
||||
default:
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
const struct pios_led_cfg * led_cfg = PIOS_BOARD_HW_DEFS_GetLedCfg(bdinfo->board_rev);
|
||||
PIOS_Assert(led_cfg);
|
||||
PIOS_LED_Init(led_cfg);
|
||||
#endif /* PIOS_INCLUDE_LED */
|
||||
|
||||
#if defined(PIOS_INCLUDE_SPI)
|
||||
/* Set up the SPI interface to the serial flash */
|
||||
|
||||
switch(bdinfo->board_rev) {
|
||||
case 0x01: // Revision 1
|
||||
case BOARD_REVISION_CC:
|
||||
if (PIOS_SPI_Init(&pios_spi_flash_accel_id, &pios_spi_flash_accel_cfg_cc)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
break;
|
||||
case 0x02: // Revision 2
|
||||
case BOARD_REVISION_CC3D:
|
||||
if (PIOS_SPI_Init(&pios_spi_flash_accel_id, &pios_spi_flash_accel_cfg_cc3d)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
@ -190,11 +182,11 @@ void PIOS_Board_Init(void) {
|
||||
#endif
|
||||
|
||||
switch(bdinfo->board_rev) {
|
||||
case 0x01: // Revision 1
|
||||
case BOARD_REVISION_CC:
|
||||
PIOS_Flash_Jedec_Init(pios_spi_flash_accel_id, 1, &flash_w25x_cfg);
|
||||
PIOS_FLASHFS_Init(&flashfs_w25x_cfg);
|
||||
break;
|
||||
case 0x02: // Revision 2
|
||||
case BOARD_REVISION_CC3D:
|
||||
PIOS_Flash_Jedec_Init(pios_spi_flash_accel_id, 0, &flash_m25p_cfg);
|
||||
PIOS_FLASHFS_Init(&flashfs_m25p_cfg);
|
||||
break;
|
||||
@ -267,10 +259,10 @@ void PIOS_Board_Init(void) {
|
||||
uint32_t pios_usb_id;
|
||||
|
||||
switch(bdinfo->board_rev) {
|
||||
case 0x01: // Revision 1
|
||||
case BOARD_REVISION_CC:
|
||||
PIOS_USB_Init(&pios_usb_id, &pios_usb_main_cfg_cc);
|
||||
break;
|
||||
case 0x02: // Revision 2
|
||||
case BOARD_REVISION_CC3D:
|
||||
PIOS_USB_Init(&pios_usb_id, &pios_usb_main_cfg_cc3d);
|
||||
break;
|
||||
default:
|
||||
@ -690,7 +682,7 @@ void PIOS_Board_Init(void) {
|
||||
#endif /* PIOS_DEBUG_ENABLE_DEBUG_PINS */
|
||||
|
||||
switch(bdinfo->board_rev) {
|
||||
case 0x01:
|
||||
case BOARD_REVISION_CC:
|
||||
// Revision 1 with invensense gyros, start the ADC
|
||||
#if defined(PIOS_INCLUDE_ADC)
|
||||
PIOS_ADC_Init(&pios_adc_cfg);
|
||||
@ -699,7 +691,7 @@ void PIOS_Board_Init(void) {
|
||||
PIOS_ADXL345_Init(pios_spi_flash_accel_id, 0);
|
||||
#endif
|
||||
break;
|
||||
case 0x02:
|
||||
case BOARD_REVISION_CC3D:
|
||||
// Revision 2 with L3GD20 gyros, start a SPI interface and connect to it
|
||||
GPIO_PinRemapConfig(GPIO_Remap_SWJ_JTAGDisable, ENABLE);
|
||||
|
||||
|
122
flight/Libraries/inc/packet_handler.h
Normal file
122
flight/Libraries/inc/packet_handler.h
Normal file
@ -0,0 +1,122 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup OpenPilotSystem OpenPilot System
|
||||
* @{
|
||||
* @addtogroup OpenPilotLibraries OpenPilot System Libraries
|
||||
* @{
|
||||
*
|
||||
* @file packet_handler.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @brief A packet handler for handeling radio packet transmission.
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
*
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* This program is free software; you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation; either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful, but
|
||||
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
|
||||
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
|
||||
* for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License along
|
||||
* with this program; if not, write to the Free Software Foundation, Inc.,
|
||||
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
*/
|
||||
|
||||
#ifndef __PACKET_HANDLER_H__
|
||||
#define __PACKET_HANDLER_H__
|
||||
|
||||
// Public defines / macros
|
||||
#define PHPacketSize(p) ((uint8_t*)(p->data) + p->header.data_size - (uint8_t*)p)
|
||||
#define PHPacketSizeECC(p) ((uint8_t*)(p->data) + p->header.data_size + RS_ECC_NPARITY - (uint8_t*)p)
|
||||
|
||||
// Public types
|
||||
typedef enum {
|
||||
PACKET_TYPE_NONE = 0,
|
||||
PACKET_TYPE_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_DATA, // data packet (packet contains user data)
|
||||
PACKET_TYPE_ACKED_DATA, // data packet that requies an ACK
|
||||
PACKET_TYPE_PPM, // PPM relay values
|
||||
PACKET_TYPE_ACK,
|
||||
PACKET_TYPE_NACK
|
||||
} PHPacketType;
|
||||
|
||||
typedef struct {
|
||||
uint32_t destination_id;
|
||||
uint32_t source_id;
|
||||
uint8_t type;
|
||||
uint8_t data_size;
|
||||
uint8_t tx_seq;
|
||||
uint8_t rx_seq;
|
||||
int8_t rssi;
|
||||
int8_t afc;
|
||||
} PHPacketHeader;
|
||||
|
||||
#define PH_MAX_DATA (PIOS_PH_MAX_PACKET - sizeof(PHPacketHeader) - RS_ECC_NPARITY)
|
||||
#define PH_PACKET_SIZE(p) (p->data + p->header.data_size - (uint8_t*)p + RS_ECC_NPARITY)
|
||||
typedef struct {
|
||||
PHPacketHeader header;
|
||||
uint8_t data[PH_MAX_DATA + RS_ECC_NPARITY];
|
||||
} PHPacket, *PHPacketHandle;
|
||||
|
||||
#define PH_PPM_DATA_SIZE(p) ((uint8_t*)((p)->ecc) - (uint8_t*)(((PHPacketHandle)(p))->data))
|
||||
typedef struct {
|
||||
PHPacketHeader header;
|
||||
uint16_t channels[PIOS_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 resets;
|
||||
uint8_t ecc[RS_ECC_NPARITY];
|
||||
} PHStatusPacket, *PHStatusPacketHandle;
|
||||
|
||||
typedef struct {
|
||||
uint8_t winSize;
|
||||
uint16_t maxConnections;
|
||||
} PacketHandlerConfig;
|
||||
|
||||
typedef int32_t (*PHOutputStream)(PHPacketHandle packet);
|
||||
typedef void (*PHDataHandler)(uint8_t *data, uint8_t len);
|
||||
typedef void (*PHStatusHandler)(PHStatusPacketHandle s);
|
||||
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 PHReleaseTXPacket(PHInstHandle h, PHPacketHandle p);
|
||||
PHPacketHandle PHGetTXPacket(PHInstHandle h);
|
||||
void PHReleaseTXPacket(PHInstHandle h, PHPacketHandle p);
|
||||
uint8_t PHTransmitPacket(PHInstHandle h, PHPacketHandle p);
|
||||
int32_t PHVerifyPacket(PHInstHandle h, PHPacketHandle p, uint16_t received_len);
|
||||
uint8_t PHReceivePacket(PHInstHandle h, PHPacketHandle p, bool rx_error);
|
||||
|
||||
#endif // __PACKET_HANDLER_H__
|
||||
|
||||
/**
|
||||
* @}
|
||||
* @}
|
||||
*/
|
507
flight/Libraries/packet_handler.c
Normal file
507
flight/Libraries/packet_handler.c
Normal file
@ -0,0 +1,507 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @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;
|
||||
uint16_t tx_seq_id;
|
||||
PHOutputStream stream;
|
||||
xSemaphoreHandle lock;
|
||||
PHOutputStream output_stream;
|
||||
PHDataHandler data_handler;
|
||||
PHStatusHandler status_handler;
|
||||
PHPPMHandler ppm_handler;
|
||||
} PHPacketData, *PHPacketDataHandle;
|
||||
|
||||
// Private functions
|
||||
static uint8_t PHLSendAck(PHPacketDataHandle data, PHPacketHandle p);
|
||||
static uint8_t PHLSendNAck(PHPacketDataHandle data, PHPacketHandle p);
|
||||
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;
|
||||
data->tx_seq_id = 0;
|
||||
|
||||
// Allocate the packet windows
|
||||
data->tx_packets = pvPortMalloc(sizeof(PHPacket) * data->cfg.winSize);
|
||||
data->rx_packets = pvPortMalloc(sizeof(PHPacket) * data->cfg.winSize);
|
||||
|
||||
// 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.winSize; ++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();
|
||||
|
||||
// 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);
|
||||
PHPacketHandle p = data->tx_packets + data->tx_win_end;
|
||||
|
||||
// Is the window full?
|
||||
uint8_t next_end = (data->tx_win_end + 1) % data->cfg.winSize;
|
||||
if(next_end == data->tx_win_start)
|
||||
{
|
||||
xSemaphoreGiveRecursive(data->lock);
|
||||
return NULL;
|
||||
}
|
||||
data->tx_win_end = next_end;
|
||||
|
||||
// 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.winSize;
|
||||
|
||||
// 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);
|
||||
PHPacketHandle p = data->rx_packets + data->rx_win_end;
|
||||
|
||||
// Is the window full?
|
||||
uint8_t next_end = (data->rx_win_end + 1) % data->cfg.winSize;
|
||||
if(next_end == data->rx_win_start)
|
||||
{
|
||||
// Release lock
|
||||
xSemaphoreGiveRecursive(data->lock);
|
||||
return NULL;
|
||||
}
|
||||
data->rx_win_end = next_end;
|
||||
|
||||
// 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.winSize;
|
||||
|
||||
// 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;
|
||||
|
||||
// If this packet doesn't require an ACK, remove it from the TX window.
|
||||
switch (p->header.type) {
|
||||
case PACKET_TYPE_READY:
|
||||
case PACKET_TYPE_NOTREADY:
|
||||
case PACKET_TYPE_DATA:
|
||||
case PACKET_TYPE_PPM:
|
||||
PHReleaseTXPacket(h, p);
|
||||
break;
|
||||
}
|
||||
|
||||
return 1;
|
||||
}
|
||||
|
||||
/**
|
||||
* Verify that a buffer contains a valid packet.
|
||||
* \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 > 0 Number of bytes consumed.
|
||||
*/
|
||||
int32_t PHVerifyPacket(PHInstHandle h, PHPacketHandle p, uint16_t received_len)
|
||||
{
|
||||
|
||||
// Verify the packet length.
|
||||
// Note: The last two bytes should be the RSSI and AFC.
|
||||
uint16_t len = PHPacketSizeECC(p);
|
||||
if (received_len < (len + 2))
|
||||
{
|
||||
DEBUG_PRINTF(1, "Packet length error %d %d\n\r", received_len, len + 2);
|
||||
return -1;
|
||||
}
|
||||
|
||||
// Attempt to correct any errors in the packet.
|
||||
decode_data((unsigned char*)p, len);
|
||||
|
||||
// Check that there were no unfixed errors.
|
||||
bool rx_error = check_syndrome() != 0;
|
||||
if(rx_error)
|
||||
{
|
||||
DEBUG_PRINTF(1, "Error in packet\n\r");
|
||||
return -2;
|
||||
}
|
||||
|
||||
return len + 2;
|
||||
}
|
||||
|
||||
/**
|
||||
* 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, bool rx_error)
|
||||
{
|
||||
PHPacketDataHandle data = (PHPacketDataHandle)h;
|
||||
uint16_t len = PHPacketSizeECC(p);
|
||||
|
||||
// Add the RSSI and AFC to the packet.
|
||||
p->header.rssi = *(((int8_t*)p) + len);
|
||||
p->header.afc = *(((int8_t*)p) + len + 1);
|
||||
|
||||
switch (p->header.type) {
|
||||
|
||||
case PACKET_TYPE_STATUS:
|
||||
|
||||
if (!rx_error)
|
||||
|
||||
// Pass on the channels to the status handler.
|
||||
if(data->status_handler)
|
||||
data->status_handler((PHStatusPacketHandle)p);
|
||||
|
||||
break;
|
||||
|
||||
case PACKET_TYPE_ACKED_DATA:
|
||||
|
||||
// Send the ACK / NACK
|
||||
if (rx_error)
|
||||
{
|
||||
DEBUG_PRINTF(1, "Sending NACK\n\r");
|
||||
PHLSendNAck(data, p);
|
||||
}
|
||||
else
|
||||
{
|
||||
|
||||
PHLSendAck(data, p);
|
||||
|
||||
// Pass on the data.
|
||||
if(data->data_handler)
|
||||
data->data_handler(p->data, p->header.data_size);
|
||||
}
|
||||
|
||||
break;
|
||||
|
||||
case PACKET_TYPE_ACK:
|
||||
{
|
||||
// Find the packet ID in the TX buffer, and free it.
|
||||
unsigned int i = 0;
|
||||
for (unsigned int i = 0; i < data->cfg.winSize; ++i)
|
||||
if (data->tx_packets[i].header.tx_seq == p->header.rx_seq)
|
||||
PHReleaseTXPacket(h, data->tx_packets + i);
|
||||
#ifdef DEBUG_LEVEL
|
||||
if (i == data->cfg.winSize)
|
||||
DEBUG_PRINTF(1, "Error finding acked packet to release\n\r");
|
||||
#endif
|
||||
}
|
||||
break;
|
||||
|
||||
case PACKET_TYPE_NACK:
|
||||
{
|
||||
// Resend the packet.
|
||||
unsigned int i = 0;
|
||||
for ( ; i < data->cfg.winSize; ++i)
|
||||
if (data->tx_packets[i].header.tx_seq == p->header.rx_seq)
|
||||
PHLTransmitPacket(data, data->tx_packets + i);
|
||||
#ifdef DEBUG_LEVEL
|
||||
if (i == data->cfg.winSize)
|
||||
DEBUG_PRINTF(1, "Error finding acked packet to NACK\n\r");
|
||||
DEBUG_PRINTF(1, "Resending after NACK\n\r");
|
||||
#endif
|
||||
}
|
||||
break;
|
||||
|
||||
case PACKET_TYPE_PPM:
|
||||
|
||||
if (!rx_error)
|
||||
|
||||
// Pass on the channels to the PPM handler.
|
||||
if(data->ppm_handler)
|
||||
data->ppm_handler(((PHPpmPacketHandle)p)->channels);
|
||||
|
||||
break;
|
||||
|
||||
case PACKET_TYPE_DATA:
|
||||
|
||||
if (!rx_error)
|
||||
|
||||
// Pass on the data to the data handler.
|
||||
if(data->data_handler)
|
||||
data->data_handler(p->data, p->header.data_size);
|
||||
|
||||
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;
|
||||
|
||||
// Set the sequence ID to the current ID.
|
||||
p->header.tx_seq = data->tx_seq_id++;
|
||||
|
||||
// Add the error correcting code.
|
||||
encode_data((unsigned char*)p, PHPacketSize(p), (unsigned char*)p);
|
||||
|
||||
// Transmit the packet using the output stream.
|
||||
if(data->output_stream(p) == -1)
|
||||
return 0;
|
||||
|
||||
return 1;
|
||||
}
|
||||
|
||||
/**
|
||||
* Send an ACK packet.
|
||||
* \param[in] data The packet handler instance data pointer.
|
||||
* \param[in] p A pointer to the packet buffer of the packet to be ACKed.
|
||||
* \return 1 Success
|
||||
* \return 0 Failure
|
||||
*/
|
||||
static uint8_t PHLSendAck(PHPacketDataHandle data, PHPacketHandle p)
|
||||
{
|
||||
|
||||
// Create the ACK message
|
||||
PHPacketHeader ack;
|
||||
ack.destination_id = p->header.source_id;
|
||||
ack.type = PACKET_TYPE_ACK;
|
||||
ack.rx_seq = p->header.tx_seq;
|
||||
ack.data_size = 0;
|
||||
|
||||
// Send the packet.
|
||||
return PHLTransmitPacket(data, (PHPacketHandle)&ack);
|
||||
}
|
||||
|
||||
/**
|
||||
* Send an NAck packet.
|
||||
* \param[in] data The packet handler instance data pointer.
|
||||
* \param[in] p A pointer to the packet buffer of the packet to be ACKed.
|
||||
* \return 1 Success
|
||||
* \return 0 Failure
|
||||
*/
|
||||
static uint8_t PHLSendNAck(PHPacketDataHandle data, PHPacketHandle p)
|
||||
{
|
||||
|
||||
// Create the NAck message
|
||||
PHPacketHeader ack;
|
||||
ack.destination_id = p->header.source_id;
|
||||
ack.type = PACKET_TYPE_NACK;
|
||||
ack.rx_seq = p->header.tx_seq;
|
||||
ack.data_size = 0;
|
||||
|
||||
// Set the packet.
|
||||
return PHLTransmitPacket(data, (PHPacketHandle)&ack);
|
||||
}
|
10
flight/Libraries/rscode/LICENSE
Normal file
10
flight/Libraries/rscode/LICENSE
Normal file
@ -0,0 +1,10 @@
|
||||
* (C) Henry Minsky (hqm@alum.mit.edu) 1991-2009
|
||||
*
|
||||
* This software library is licensed under terms of the GNU GENERAL
|
||||
* PUBLIC LICENSE. [See file gpl.txt]
|
||||
*
|
||||
* Commercial licensing is available under a separate license, please
|
||||
* contact author for details.
|
||||
*
|
||||
* Latest source code and other info at http://rscode.sourceforge.net
|
||||
|
50
flight/Libraries/rscode/Makefile
Normal file
50
flight/Libraries/rscode/Makefile
Normal file
@ -0,0 +1,50 @@
|
||||
# Makefile for Cross Interleaved Reed Solomon encoder/decoder
|
||||
#
|
||||
# (c) Henry Minsky, Universal Access 1991-1996
|
||||
#
|
||||
|
||||
RANLIB = ranlib
|
||||
AR = ar
|
||||
|
||||
|
||||
VERSION = 1.0
|
||||
DIRNAME= rscode-$(VERSION)
|
||||
|
||||
|
||||
CC = gcc
|
||||
# OPTIMIZE_FLAGS = -O69
|
||||
DEBUG_FLAGS = -g
|
||||
CFLAGS = -Wall -Wstrict-prototypes $(OPTIMIZE_FLAGS) $(DEBUG_FLAGS) -I..
|
||||
LDFLAGS = $(OPTIMIZE_FLAGS) $(DEBUG_FLAGS)
|
||||
|
||||
LIB_CSRC = rs.c galois.c berlekamp.c crcgen.c
|
||||
LIB_HSRC = ecc.h
|
||||
LIB_OBJS = rs.o galois.o berlekamp.o crcgen.o
|
||||
|
||||
TARGET_LIB = libecc.a
|
||||
TEST_PROGS = example
|
||||
|
||||
TARGETS = $(TARGET_LIB) $(TEST_PROGS)
|
||||
|
||||
all: $(TARGETS)
|
||||
|
||||
$(TARGET_LIB): $(LIB_OBJS)
|
||||
$(RM) $@
|
||||
$(AR) cq $@ $(LIB_OBJS)
|
||||
if [ "$(RANLIB)" ]; then $(RANLIB) $@; fi
|
||||
|
||||
example: example.o galois.o berlekamp.o crcgen.o rs.o
|
||||
gcc -o example example.o -L. -lecc
|
||||
|
||||
clean:
|
||||
rm -f *.o example libecc.a
|
||||
rm -f *~
|
||||
|
||||
dist:
|
||||
(cd ..; tar -cvf rscode-$(VERSION).tar $(DIRNAME))
|
||||
|
||||
depend:
|
||||
makedepend $(SRCS)
|
||||
|
||||
# DO NOT DELETE THIS LINE -- make depend depends on it.
|
||||
|
27
flight/Libraries/rscode/README
Normal file
27
flight/Libraries/rscode/README
Normal file
@ -0,0 +1,27 @@
|
||||
RSCODE version 1.3
|
||||
|
||||
See the files
|
||||
|
||||
config.doc documentation of some compile time parameters
|
||||
rs.doc overview of the Reed-Solomon coding program
|
||||
rs.man a man page, slightly outdated at this point
|
||||
example.c a simple example of encoding,decoding, and error correction
|
||||
|
||||
Makefile should work on a Sun system, may require GNU make.
|
||||
|
||||
|
||||
Henry Minsky
|
||||
hqm@alum.mit.edu
|
||||
|
||||
|
||||
* (c) Henry Minsky (hqm@alum.mit.edu) 1991-2009
|
||||
*
|
||||
* This software library is licensed under terms of the GNU GENERAL
|
||||
* PUBLIC LICENSE. (See gpl.txt)
|
||||
*
|
||||
* Commercial licensing is available under a separate license, please
|
||||
* contact author for details.
|
||||
*
|
||||
* Source code is available at http://rscode.sourceforge.net
|
||||
|
||||
|
324
flight/Libraries/rscode/berlekamp.c
Normal file
324
flight/Libraries/rscode/berlekamp.c
Normal file
@ -0,0 +1,324 @@
|
||||
/***********************************************************************
|
||||
* Copyright Henry Minsky (hqm@alum.mit.edu) 1991-2009
|
||||
*
|
||||
* This software library is licensed under terms of the GNU GENERAL
|
||||
* PUBLIC LICENSE
|
||||
*
|
||||
*
|
||||
* RSCODE 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.
|
||||
*
|
||||
* RSCODE 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 Rscode. If not, see <http://www.gnu.org/licenses/>.
|
||||
*
|
||||
* Commercial licensing is available under a separate license, please
|
||||
* contact author for details.
|
||||
*
|
||||
* Source code is available at http://rscode.sourceforge.net
|
||||
* Berlekamp-Peterson and Berlekamp-Massey Algorithms for error-location
|
||||
*
|
||||
* From Cain, Clark, "Error-Correction Coding For Digital Communications", pp. 205.
|
||||
*
|
||||
* This finds the coefficients of the error locator polynomial.
|
||||
*
|
||||
* The roots are then found by looking for the values of a^n
|
||||
* where evaluating the polynomial yields zero.
|
||||
*
|
||||
* Error correction is done using the error-evaluator equation on pp 207.
|
||||
*
|
||||
*/
|
||||
|
||||
#include <stdio.h>
|
||||
#include "ecc.h"
|
||||
|
||||
/* The Error Locator Polynomial, also known as Lambda or Sigma. Lambda[0] == 1 */
|
||||
static int Lambda[MAXDEG];
|
||||
|
||||
/* The Error Evaluator Polynomial */
|
||||
static int Omega[MAXDEG];
|
||||
|
||||
/* local ANSI declarations */
|
||||
static int compute_discrepancy(int lambda[], int S[], int L, int n);
|
||||
static void init_gamma(int gamma[]);
|
||||
static void compute_modified_omega (void);
|
||||
static void mul_z_poly (int src[]);
|
||||
|
||||
/* error locations found using Chien's search*/
|
||||
static int ErrorLocs[256];
|
||||
static int NErrors;
|
||||
|
||||
/* erasure flags */
|
||||
static int ErasureLocs[256];
|
||||
static int NErasures;
|
||||
|
||||
/* From Cain, Clark, "Error-Correction Coding For Digital Communications", pp. 216. */
|
||||
void
|
||||
Modified_Berlekamp_Massey (void)
|
||||
{
|
||||
int n, L, L2, k, d, i;
|
||||
int psi[MAXDEG], psi2[MAXDEG], D[MAXDEG];
|
||||
int gamma[MAXDEG];
|
||||
|
||||
/* initialize Gamma, the erasure locator polynomial */
|
||||
init_gamma(gamma);
|
||||
|
||||
/* initialize to z */
|
||||
copy_poly(D, gamma);
|
||||
mul_z_poly(D);
|
||||
|
||||
copy_poly(psi, gamma);
|
||||
k = -1; L = NErasures;
|
||||
|
||||
for (n = NErasures; n < RS_ECC_NPARITY; n++) {
|
||||
|
||||
d = compute_discrepancy(psi, synBytes, L, n);
|
||||
|
||||
if (d != 0) {
|
||||
|
||||
/* psi2 = psi - d*D */
|
||||
for (i = 0; i < MAXDEG; i++) psi2[i] = psi[i] ^ gmult(d, D[i]);
|
||||
|
||||
|
||||
if (L < (n-k)) {
|
||||
L2 = n-k;
|
||||
k = n-L;
|
||||
/* D = scale_poly(ginv(d), psi); */
|
||||
for (i = 0; i < MAXDEG; i++) D[i] = gmult(psi[i], ginv(d));
|
||||
L = L2;
|
||||
}
|
||||
|
||||
/* psi = psi2 */
|
||||
for (i = 0; i < MAXDEG; i++) psi[i] = psi2[i];
|
||||
}
|
||||
|
||||
mul_z_poly(D);
|
||||
}
|
||||
|
||||
for(i = 0; i < MAXDEG; i++) Lambda[i] = psi[i];
|
||||
compute_modified_omega();
|
||||
|
||||
|
||||
}
|
||||
|
||||
/* given Psi (called Lambda in Modified_Berlekamp_Massey) and synBytes,
|
||||
compute the combined erasure/error evaluator polynomial as
|
||||
Psi*S mod z^4
|
||||
*/
|
||||
void
|
||||
compute_modified_omega ()
|
||||
{
|
||||
int i;
|
||||
int product[MAXDEG*2];
|
||||
|
||||
mult_polys(product, Lambda, synBytes);
|
||||
zero_poly(Omega);
|
||||
for(i = 0; i < RS_ECC_NPARITY; i++) Omega[i] = product[i];
|
||||
|
||||
}
|
||||
|
||||
/* polynomial multiplication */
|
||||
void
|
||||
mult_polys (int dst[], int p1[], int p2[])
|
||||
{
|
||||
int i, j;
|
||||
int tmp1[MAXDEG*2];
|
||||
|
||||
for (i=0; i < (MAXDEG*2); i++) dst[i] = 0;
|
||||
|
||||
for (i = 0; i < MAXDEG; i++) {
|
||||
for(j=MAXDEG; j<(MAXDEG*2); j++) tmp1[j]=0;
|
||||
|
||||
/* scale tmp1 by p1[i] */
|
||||
for(j=0; j<MAXDEG; j++) tmp1[j]=gmult(p2[j], p1[i]);
|
||||
/* and mult (shift) tmp1 right by i */
|
||||
for (j = (MAXDEG*2)-1; j >= i; j--) tmp1[j] = tmp1[j-i];
|
||||
for (j = 0; j < i; j++) tmp1[j] = 0;
|
||||
|
||||
/* add into partial product */
|
||||
for(j=0; j < (MAXDEG*2); j++) dst[j] ^= tmp1[j];
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
|
||||
/* gamma = product (1-z*a^Ij) for erasure locs Ij */
|
||||
void
|
||||
init_gamma (int gamma[])
|
||||
{
|
||||
int e, tmp[MAXDEG];
|
||||
|
||||
zero_poly(gamma);
|
||||
zero_poly(tmp);
|
||||
gamma[0] = 1;
|
||||
|
||||
for (e = 0; e < NErasures; e++) {
|
||||
copy_poly(tmp, gamma);
|
||||
scale_poly(gexp[ErasureLocs[e]], tmp);
|
||||
mul_z_poly(tmp);
|
||||
add_polys(gamma, tmp);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
|
||||
void
|
||||
compute_next_omega (int d, int A[], int dst[], int src[])
|
||||
{
|
||||
int i;
|
||||
for ( i = 0; i < MAXDEG; i++) {
|
||||
dst[i] = src[i] ^ gmult(d, A[i]);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
|
||||
int
|
||||
compute_discrepancy (int lambda[], int S[], int L, int n)
|
||||
{
|
||||
int i, sum=0;
|
||||
|
||||
for (i = 0; i <= L; i++)
|
||||
sum ^= gmult(lambda[i], S[n-i]);
|
||||
return (sum);
|
||||
}
|
||||
|
||||
/********** polynomial arithmetic *******************/
|
||||
|
||||
void add_polys (int dst[], int src[])
|
||||
{
|
||||
int i;
|
||||
for (i = 0; i < MAXDEG; i++) dst[i] ^= src[i];
|
||||
}
|
||||
|
||||
void copy_poly (int dst[], int src[])
|
||||
{
|
||||
int i;
|
||||
for (i = 0; i < MAXDEG; i++) dst[i] = src[i];
|
||||
}
|
||||
|
||||
void scale_poly (int k, int poly[])
|
||||
{
|
||||
int i;
|
||||
for (i = 0; i < MAXDEG; i++) poly[i] = gmult(k, poly[i]);
|
||||
}
|
||||
|
||||
|
||||
void zero_poly (int poly[])
|
||||
{
|
||||
int i;
|
||||
for (i = 0; i < MAXDEG; i++) poly[i] = 0;
|
||||
}
|
||||
|
||||
|
||||
/* multiply by z, i.e., shift right by 1 */
|
||||
static void mul_z_poly (int src[])
|
||||
{
|
||||
int i;
|
||||
for (i = MAXDEG-1; i > 0; i--) src[i] = src[i-1];
|
||||
src[0] = 0;
|
||||
}
|
||||
|
||||
|
||||
/* Finds all the roots of an error-locator polynomial with coefficients
|
||||
* Lambda[j] by evaluating Lambda at successive values of alpha.
|
||||
*
|
||||
* This can be tested with the decoder's equations case.
|
||||
*/
|
||||
|
||||
|
||||
void
|
||||
Find_Roots (void)
|
||||
{
|
||||
int sum, r, k;
|
||||
NErrors = 0;
|
||||
|
||||
for (r = 1; r < 256; r++) {
|
||||
sum = 0;
|
||||
/* evaluate lambda at r */
|
||||
for (k = 0; k < RS_ECC_NPARITY+1; k++) {
|
||||
sum ^= gmult(gexp[(k*r)%255], Lambda[k]);
|
||||
}
|
||||
if (sum == 0)
|
||||
{
|
||||
ErrorLocs[NErrors] = (255-r); NErrors++;
|
||||
//if (DEBUG) fprintf(stderr, "Root found at r = %d, (255-r) = %d\n", r, (255-r));
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/* Combined Erasure And Error Magnitude Computation
|
||||
*
|
||||
* Pass in the codeword, its size in bytes, as well as
|
||||
* an array of any known erasure locations, along the number
|
||||
* of these erasures.
|
||||
*
|
||||
* Evaluate Omega(actually Psi)/Lambda' at the roots
|
||||
* alpha^(-i) for error locs i.
|
||||
*
|
||||
* Returns 1 if everything ok, or 0 if an out-of-bounds error is found
|
||||
*
|
||||
*/
|
||||
|
||||
int
|
||||
correct_errors_erasures (unsigned char codeword[],
|
||||
int csize,
|
||||
int nerasures,
|
||||
int erasures[])
|
||||
{
|
||||
int r, i, j, err;
|
||||
|
||||
/* If you want to take advantage of erasure correction, be sure to
|
||||
set NErasures and ErasureLocs[] with the locations of erasures.
|
||||
*/
|
||||
NErasures = nerasures;
|
||||
for (i = 0; i < NErasures; i++) ErasureLocs[i] = erasures[i];
|
||||
|
||||
Modified_Berlekamp_Massey();
|
||||
Find_Roots();
|
||||
|
||||
|
||||
if ((NErrors <= RS_ECC_NPARITY) && NErrors > 0) {
|
||||
|
||||
/* first check for illegal error locs */
|
||||
for (r = 0; r < NErrors; r++) {
|
||||
if (ErrorLocs[r] >= csize) {
|
||||
//if (DEBUG) fprintf(stderr, "Error loc i=%d outside of codeword length %d\n", i, csize);
|
||||
return(0);
|
||||
}
|
||||
}
|
||||
|
||||
for (r = 0; r < NErrors; r++) {
|
||||
int num, denom;
|
||||
i = ErrorLocs[r];
|
||||
/* evaluate Omega at alpha^(-i) */
|
||||
|
||||
num = 0;
|
||||
for (j = 0; j < MAXDEG; j++)
|
||||
num ^= gmult(Omega[j], gexp[((255-i)*j)%255]);
|
||||
|
||||
/* evaluate Lambda' (derivative) at alpha^(-i) ; all odd powers disappear */
|
||||
denom = 0;
|
||||
for (j = 1; j < MAXDEG; j += 2) {
|
||||
denom ^= gmult(Lambda[j], gexp[((255-i)*(j-1)) % 255]);
|
||||
}
|
||||
|
||||
err = gmult(num, ginv(denom));
|
||||
//if (DEBUG) fprintf(stderr, "Error magnitude %#x at loc %d\n", err, csize-i);
|
||||
|
||||
codeword[csize-i-1] ^= err;
|
||||
}
|
||||
return(1);
|
||||
}
|
||||
else {
|
||||
//if (DEBUG && NErrors) fprintf(stderr, "Uncorrectable codeword\n");
|
||||
return(0);
|
||||
}
|
||||
}
|
||||
|
18
flight/Libraries/rscode/config.doc
Normal file
18
flight/Libraries/rscode/config.doc
Normal file
@ -0,0 +1,18 @@
|
||||
The basic coding parameters are defined using
|
||||
macros, and an executable can be made by compiling using macro
|
||||
definitions defining the values of the following names in the file
|
||||
"ecc.h":
|
||||
|
||||
The important compile time parameter is the number of parity bytes,
|
||||
specified by the #define NPAR.
|
||||
|
||||
The library is shipped with
|
||||
|
||||
#define NPAR 4
|
||||
|
||||
The error-correction routines are polynomial in the number of
|
||||
parity bytes, so try to keep NPAR small for high performance.
|
||||
|
||||
Remember, the sum of the message length (in bytes) plus parity bytes
|
||||
must be less than or equal to 255.
|
||||
|
66
flight/Libraries/rscode/crcgen.c
Normal file
66
flight/Libraries/rscode/crcgen.c
Normal file
@ -0,0 +1,66 @@
|
||||
/*****************************
|
||||
* Copyright Henry Minsky (hqm@alum.mit.edu) 1991-2009
|
||||
*
|
||||
* This software library is licensed under terms of the GNU GENERAL
|
||||
* PUBLIC LICENSE
|
||||
*
|
||||
* RSCODE 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.
|
||||
*
|
||||
* RSCODE 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 Rscode. If not, see <http://www.gnu.org/licenses/>.
|
||||
|
||||
* Commercial licensing is available under a separate license, please
|
||||
* contact author for details.
|
||||
*
|
||||
* Source code is available at http://rscode.sourceforge.net
|
||||
*
|
||||
* CRC-CCITT generator simulator for byte wide data.
|
||||
*
|
||||
*
|
||||
* CRC-CCITT = x^16 + x^12 + x^5 + 1
|
||||
*
|
||||
*
|
||||
******************************/
|
||||
|
||||
|
||||
#include "ecc.h"
|
||||
|
||||
BIT16 crchware(BIT16 data, BIT16 genpoly, BIT16 accum);
|
||||
|
||||
/* Computes the CRC-CCITT checksum on array of byte data, length len
|
||||
*/
|
||||
BIT16 crc_ccitt(unsigned char *msg, int len)
|
||||
{
|
||||
int i;
|
||||
BIT16 acc = 0;
|
||||
|
||||
for (i = 0; i < len; i++) {
|
||||
acc = crchware((BIT16) msg[i], (BIT16) 0x1021, acc);
|
||||
}
|
||||
|
||||
return(acc);
|
||||
}
|
||||
|
||||
/* models crc hardware (minor variation on polynomial division algorithm) */
|
||||
BIT16 crchware(BIT16 data, BIT16 genpoly, BIT16 accum)
|
||||
{
|
||||
static BIT16 i;
|
||||
data <<= 8;
|
||||
for (i = 8; i > 0; i--) {
|
||||
if ((data ^ accum) & 0x8000)
|
||||
accum = ((accum << 1) ^ genpoly) & 0xFFFF;
|
||||
else
|
||||
accum = (accum<<1) & 0xFFFF;
|
||||
data = (data<<1) & 0xFFFF;
|
||||
}
|
||||
return (accum);
|
||||
}
|
||||
|
98
flight/Libraries/rscode/ecc.h
Normal file
98
flight/Libraries/rscode/ecc.h
Normal file
@ -0,0 +1,98 @@
|
||||
/* Reed Solomon Coding for glyphs
|
||||
* Copyright Henry Minsky (hqm@alum.mit.edu) 1991-2009
|
||||
*
|
||||
* This software library is licensed under terms of the GNU GENERAL
|
||||
* PUBLIC LICENSE
|
||||
*
|
||||
* RSCODE 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.
|
||||
*
|
||||
* RSCODE 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 Rscode. If not, see <http://www.gnu.org/licenses/>.
|
||||
*
|
||||
* Source code is available at http://rscode.sourceforge.net
|
||||
*
|
||||
* Commercial licensing is available under a separate license, please
|
||||
* contact author for details.
|
||||
*
|
||||
*/
|
||||
|
||||
/****************************************************************
|
||||
|
||||
Below is NPAR, the only compile-time parameter you should have to
|
||||
modify.
|
||||
|
||||
It is the number of parity bytes which will be appended to
|
||||
your data to create a codeword.
|
||||
|
||||
Note that the maximum codeword size is 255, so the
|
||||
sum of your message length plus parity should be less than
|
||||
or equal to this maximum limit.
|
||||
|
||||
In practice, you will get slooow error correction and decoding
|
||||
if you use more than a reasonably small number of parity bytes.
|
||||
(say, 10 or 20)
|
||||
|
||||
****************************************************************/
|
||||
|
||||
/****************************************************************/
|
||||
|
||||
|
||||
#include <openpilot.h>
|
||||
|
||||
#define TRUE 1
|
||||
#define FALSE 0
|
||||
|
||||
typedef unsigned long BIT32;
|
||||
typedef unsigned short BIT16;
|
||||
|
||||
/* **************************************************************** */
|
||||
|
||||
/* Maximum degree of various polynomials. */
|
||||
#define MAXDEG (RS_ECC_NPARITY*2)
|
||||
|
||||
/*************************************/
|
||||
/* Encoder parity bytes */
|
||||
extern int pBytes[MAXDEG];
|
||||
|
||||
/* Decoder syndrome bytes */
|
||||
extern int synBytes[MAXDEG];
|
||||
|
||||
/* print debugging info */
|
||||
extern int DEBUG;
|
||||
|
||||
/* Reed Solomon encode/decode routines */
|
||||
void initialize_ecc (void);
|
||||
int check_syndrome (void);
|
||||
void decode_data (unsigned char data[], int nbytes);
|
||||
void encode_data (unsigned char msg[], int nbytes, unsigned char dst[]);
|
||||
|
||||
/* CRC-CCITT checksum generator */
|
||||
BIT16 crc_ccitt(unsigned char *msg, int len);
|
||||
|
||||
/* galois arithmetic tables */
|
||||
extern const int gexp[];
|
||||
extern const int glog[];
|
||||
|
||||
void init_galois_tables (void);
|
||||
int ginv(int elt);
|
||||
int gmult(int a, int b);
|
||||
|
||||
|
||||
/* Error location routines */
|
||||
int correct_errors_erasures (unsigned char codeword[], int csize,int nerasures, int erasures[]);
|
||||
|
||||
/* polynomial arithmetic */
|
||||
void add_polys(int dst[], int src[]) ;
|
||||
void scale_poly(int k, int poly[]);
|
||||
void mult_polys(int dst[], int p1[], int p2[]);
|
||||
|
||||
void copy_poly(int dst[], int src[]);
|
||||
void zero_poly(int poly[]);
|
128
flight/Libraries/rscode/example.c
Normal file
128
flight/Libraries/rscode/example.c
Normal file
@ -0,0 +1,128 @@
|
||||
/* Example use of Reed-Solomon library
|
||||
*
|
||||
* Copyright Henry Minsky (hqm@alum.mit.edu) 1991-2009
|
||||
*
|
||||
* This software library is licensed under terms of the GNU GENERAL
|
||||
* PUBLIC LICENSE
|
||||
*
|
||||
* RSCODE 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.
|
||||
*
|
||||
* RSCODE 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 Rscode. If not, see <http://www.gnu.org/licenses/>.
|
||||
|
||||
* Commercial licensing is available under a separate license, please
|
||||
* contact author for details.
|
||||
*
|
||||
* This same code demonstrates the use of the encodier and
|
||||
* decoder/error-correction routines.
|
||||
*
|
||||
* We are assuming we have at least four bytes of parity (NPAR >= 4).
|
||||
*
|
||||
* This gives us the ability to correct up to two errors, or
|
||||
* four erasures.
|
||||
*
|
||||
* In general, with E errors, and K erasures, you will need
|
||||
* 2E + K bytes of parity to be able to correct the codeword
|
||||
* back to recover the original message data.
|
||||
*
|
||||
* You could say that each error 'consumes' two bytes of the parity,
|
||||
* whereas each erasure 'consumes' one byte.
|
||||
*
|
||||
* Thus, as demonstrated below, we can inject one error (location unknown)
|
||||
* and two erasures (with their locations specified) and the
|
||||
* error-correction routine will be able to correct the codeword
|
||||
* back to the original message.
|
||||
* */
|
||||
|
||||
#include <stdio.h>
|
||||
#include <stdlib.h>
|
||||
#include "ecc.h"
|
||||
|
||||
unsigned char msg[] = "Nervously I loaded the twin ducks aboard the revolving pl\
|
||||
atform.";
|
||||
unsigned char codeword[256];
|
||||
|
||||
/* Some debugging routines to introduce errors or erasures
|
||||
into a codeword.
|
||||
*/
|
||||
|
||||
/* Introduce a byte error at LOC */
|
||||
void
|
||||
byte_err (int err, int loc, unsigned char *dst)
|
||||
{
|
||||
printf("Adding Error at loc %d, data %#x\n", loc, dst[loc-1]);
|
||||
dst[loc-1] ^= err;
|
||||
}
|
||||
|
||||
/* Pass in location of error (first byte position is
|
||||
labeled starting at 1, not 0), and the codeword.
|
||||
*/
|
||||
void
|
||||
byte_erasure (int loc, unsigned char dst[], int cwsize, int erasures[])
|
||||
{
|
||||
printf("Erasure at loc %d, data %#x\n", loc, dst[loc-1]);
|
||||
dst[loc-1] = 0;
|
||||
}
|
||||
|
||||
|
||||
int
|
||||
main (int argc, char *argv[])
|
||||
{
|
||||
|
||||
int erasures[16];
|
||||
int nerasures = 0;
|
||||
|
||||
/* Initialization the ECC library */
|
||||
|
||||
initialize_ecc ();
|
||||
|
||||
/* ************** */
|
||||
|
||||
/* Encode data into codeword, adding NPAR parity bytes */
|
||||
encode_data(msg, sizeof(msg), codeword);
|
||||
|
||||
printf("Encoded data is: \"%s\"\n", codeword);
|
||||
|
||||
#define ML (sizeof (msg) + NPAR)
|
||||
|
||||
|
||||
/* Add one error and two erasures */
|
||||
byte_err(0x35, 3, codeword);
|
||||
|
||||
byte_err(0x23, 17, codeword);
|
||||
byte_err(0x34, 19, codeword);
|
||||
|
||||
|
||||
printf("with some errors: \"%s\"\n", codeword);
|
||||
|
||||
/* We need to indicate the position of the erasures. Eraseure
|
||||
positions are indexed (1 based) from the end of the message... */
|
||||
|
||||
erasures[nerasures++] = ML-17;
|
||||
erasures[nerasures++] = ML-19;
|
||||
|
||||
|
||||
/* Now decode -- encoded codeword size must be passed */
|
||||
decode_data(codeword, ML);
|
||||
|
||||
/* check if syndrome is all zeros */
|
||||
if (check_syndrome () != 0) {
|
||||
correct_errors_erasures (codeword,
|
||||
ML,
|
||||
nerasures,
|
||||
erasures);
|
||||
|
||||
printf("Corrected codeword: \"%s\"\n", codeword);
|
||||
}
|
||||
|
||||
exit(0);
|
||||
}
|
||||
|
164
flight/Libraries/rscode/galois.c
Normal file
164
flight/Libraries/rscode/galois.c
Normal file
@ -0,0 +1,164 @@
|
||||
/*****************************
|
||||
* Copyright Henry Minsky (hqm@alum.mit.edu) 1991-2009
|
||||
*
|
||||
* This software library is licensed under terms of the GNU GENERAL
|
||||
* PUBLIC LICENSE
|
||||
*
|
||||
* RSCODE 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.
|
||||
*
|
||||
* RSCODE 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 Rscode. If not, see <http://www.gnu.org/licenses/>.
|
||||
|
||||
* Commercial licensing is available under a separate license, please
|
||||
* contact author for details.
|
||||
*
|
||||
* Source code is available at http://rscode.sourceforge.net
|
||||
*
|
||||
*
|
||||
* Multiplication and Arithmetic on Galois Field GF(256)
|
||||
*
|
||||
* From Mee, Daniel, "Magnetic Recording, Volume III", Ch. 5 by Patel.
|
||||
*
|
||||
*
|
||||
******************************/
|
||||
|
||||
|
||||
#include <stdio.h>
|
||||
#include <stdlib.h>
|
||||
#include "ecc.h"
|
||||
|
||||
/* This is one of 14 irreducible polynomials
|
||||
* of degree 8 and cycle length 255. (Ch 5, pp. 275, Magnetic Recording)
|
||||
* The high order 1 bit is implicit */
|
||||
/* x^8 + x^4 + x^3 + x^2 + 1 */
|
||||
#define PPOLY 0x1D
|
||||
|
||||
|
||||
const int gexp[512] = {
|
||||
1, 2, 4, 8, 16, 32, 64, 128, 29, 58, 116, 232, 205, 135, 19, 38,
|
||||
76, 152, 45, 90, 180, 117, 234, 201, 143, 3, 6, 12, 24, 48, 96, 192,
|
||||
157, 39, 78, 156, 37, 74, 148, 53, 106, 212, 181, 119, 238, 193, 159, 35,
|
||||
70, 140, 5, 10, 20, 40, 80, 160, 93, 186, 105, 210, 185, 111, 222, 161,
|
||||
95, 190, 97, 194, 153, 47, 94, 188, 101, 202, 137, 15, 30, 60, 120, 240,
|
||||
253, 231, 211, 187, 107, 214, 177, 127, 254, 225, 223, 163, 91, 182, 113, 226,
|
||||
217, 175, 67, 134, 17, 34, 68, 136, 13, 26, 52, 104, 208, 189, 103, 206,
|
||||
129, 31, 62, 124, 248, 237, 199, 147, 59, 118, 236, 197, 151, 51, 102, 204,
|
||||
133, 23, 46, 92, 184, 109, 218, 169, 79, 158, 33, 66, 132, 21, 42, 84,
|
||||
168, 77, 154, 41, 82, 164, 85, 170, 73, 146, 57, 114, 228, 213, 183, 115,
|
||||
230, 209, 191, 99, 198, 145, 63, 126, 252, 229, 215, 179, 123, 246, 241, 255,
|
||||
227, 219, 171, 75, 150, 49, 98, 196, 149, 55, 110, 220, 165, 87, 174, 65,
|
||||
130, 25, 50, 100, 200, 141, 7, 14, 28, 56, 112, 224, 221, 167, 83, 166,
|
||||
81, 162, 89, 178, 121, 242, 249, 239, 195, 155, 43, 86, 172, 69, 138, 9,
|
||||
18, 36, 72, 144, 61, 122, 244, 245, 247, 243, 251, 235, 203, 139, 11, 22,
|
||||
44, 88, 176, 125, 250, 233, 207, 131, 27, 54, 108, 216, 173, 71, 142, 1,
|
||||
2, 4, 8, 16, 32, 64, 128, 29, 58, 116, 232, 205, 135, 19, 38, 76,
|
||||
152, 45, 90, 180, 117, 234, 201, 143, 3, 6, 12, 24, 48, 96, 192, 157,
|
||||
39, 78, 156, 37, 74, 148, 53, 106, 212, 181, 119, 238, 193, 159, 35, 70,
|
||||
140, 5, 10, 20, 40, 80, 160, 93, 186, 105, 210, 185, 111, 222, 161, 95,
|
||||
190, 97, 194, 153, 47, 94, 188, 101, 202, 137, 15, 30, 60, 120, 240, 253,
|
||||
231, 211, 187, 107, 214, 177, 127, 254, 225, 223, 163, 91, 182, 113, 226, 217,
|
||||
175, 67, 134, 17, 34, 68, 136, 13, 26, 52, 104, 208, 189, 103, 206, 129,
|
||||
31, 62, 124, 248, 237, 199, 147, 59, 118, 236, 197, 151, 51, 102, 204, 133,
|
||||
23, 46, 92, 184, 109, 218, 169, 79, 158, 33, 66, 132, 21, 42, 84, 168,
|
||||
77, 154, 41, 82, 164, 85, 170, 73, 146, 57, 114, 228, 213, 183, 115, 230,
|
||||
209, 191, 99, 198, 145, 63, 126, 252, 229, 215, 179, 123, 246, 241, 255, 227,
|
||||
219, 171, 75, 150, 49, 98, 196, 149, 55, 110, 220, 165, 87, 174, 65, 130,
|
||||
25, 50, 100, 200, 141, 7, 14, 28, 56, 112, 224, 221, 167, 83, 166, 81,
|
||||
162, 89, 178, 121, 242, 249, 239, 195, 155, 43, 86, 172, 69, 138, 9, 18,
|
||||
36, 72, 144, 61, 122, 244, 245, 247, 243, 251, 235, 203, 139, 11, 22, 44,
|
||||
88, 176, 125, 250, 233, 207, 131, 27, 54, 108, 216, 173, 71, 142, 1, 0,
|
||||
};
|
||||
const int glog[256] = {
|
||||
0, 0, 1, 25, 2, 50, 26, 198, 3, 223, 51, 238, 27, 104, 199, 75,
|
||||
4, 100, 224, 14, 52, 141, 239, 129, 28, 193, 105, 248, 200, 8, 76, 113,
|
||||
5, 138, 101, 47, 225, 36, 15, 33, 53, 147, 142, 218, 240, 18, 130, 69,
|
||||
29, 181, 194, 125, 106, 39, 249, 185, 201, 154, 9, 120, 77, 228, 114, 166,
|
||||
6, 191, 139, 98, 102, 221, 48, 253, 226, 152, 37, 179, 16, 145, 34, 136,
|
||||
54, 208, 148, 206, 143, 150, 219, 189, 241, 210, 19, 92, 131, 56, 70, 64,
|
||||
30, 66, 182, 163, 195, 72, 126, 110, 107, 58, 40, 84, 250, 133, 186, 61,
|
||||
202, 94, 155, 159, 10, 21, 121, 43, 78, 212, 229, 172, 115, 243, 167, 87,
|
||||
7, 112, 192, 247, 140, 128, 99, 13, 103, 74, 222, 237, 49, 197, 254, 24,
|
||||
227, 165, 153, 119, 38, 184, 180, 124, 17, 68, 146, 217, 35, 32, 137, 46,
|
||||
55, 63, 209, 91, 149, 188, 207, 205, 144, 135, 151, 178, 220, 252, 190, 97,
|
||||
242, 86, 211, 171, 20, 42, 93, 158, 132, 60, 57, 83, 71, 109, 65, 162,
|
||||
31, 45, 67, 216, 183, 123, 164, 118, 196, 23, 73, 236, 127, 12, 111, 246,
|
||||
108, 161, 59, 82, 41, 157, 85, 170, 251, 96, 134, 177, 187, 204, 62, 90,
|
||||
203, 89, 95, 176, 156, 169, 160, 81, 11, 245, 22, 235, 122, 117, 44, 215,
|
||||
79, 174, 213, 233, 230, 231, 173, 232, 116, 214, 244, 234, 168, 80, 88, 175,
|
||||
};
|
||||
|
||||
|
||||
//static void init_exp_table (void);
|
||||
|
||||
|
||||
void
|
||||
init_galois_tables (void)
|
||||
{
|
||||
/* initialize the table of powers of alpha */
|
||||
//init_exp_table();
|
||||
}
|
||||
|
||||
|
||||
#ifdef NEVER
|
||||
static void
|
||||
init_exp_table (void)
|
||||
{
|
||||
int i, z;
|
||||
int pinit,p1,p2,p3,p4,p5,p6,p7,p8;
|
||||
|
||||
pinit = p2 = p3 = p4 = p5 = p6 = p7 = p8 = 0;
|
||||
p1 = 1;
|
||||
|
||||
gexp[0] = 1;
|
||||
gexp[255] = gexp[0];
|
||||
glog[0] = 0; /* shouldn't log[0] be an error? */
|
||||
|
||||
for (i = 1; i < 256; i++) {
|
||||
pinit = p8;
|
||||
p8 = p7;
|
||||
p7 = p6;
|
||||
p6 = p5;
|
||||
p5 = p4 ^ pinit;
|
||||
p4 = p3 ^ pinit;
|
||||
p3 = p2 ^ pinit;
|
||||
p2 = p1;
|
||||
p1 = pinit;
|
||||
gexp[i] = p1 + p2*2 + p3*4 + p4*8 + p5*16 + p6*32 + p7*64 + p8*128;
|
||||
gexp[i+255] = gexp[i];
|
||||
}
|
||||
|
||||
for (i = 1; i < 256; i++) {
|
||||
for (z = 0; z < 256; z++) {
|
||||
if (gexp[z] == i) {
|
||||
glog[i] = z;
|
||||
break;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
/* multiplication using logarithms */
|
||||
int gmult(int a, int b)
|
||||
{
|
||||
int i,j;
|
||||
if (a==0 || b == 0) return (0);
|
||||
i = glog[a];
|
||||
j = glog[b];
|
||||
return (gexp[i+j]);
|
||||
}
|
||||
|
||||
|
||||
int ginv (int elt)
|
||||
{
|
||||
return (gexp[255-glog[elt]]);
|
||||
}
|
||||
|
674
flight/Libraries/rscode/gpl.txt
Normal file
674
flight/Libraries/rscode/gpl.txt
Normal file
@ -0,0 +1,674 @@
|
||||
GNU GENERAL PUBLIC LICENSE
|
||||
Version 3, 29 June 2007
|
||||
|
||||
Copyright (C) 2007 Free Software Foundation, Inc. <http://fsf.org/>
|
||||
Everyone is permitted to copy and distribute verbatim copies
|
||||
of this license document, but changing it is not allowed.
|
||||
|
||||
Preamble
|
||||
|
||||
The GNU General Public License is a free, copyleft license for
|
||||
software and other kinds of works.
|
||||
|
||||
The licenses for most software and other practical works are designed
|
||||
to take away your freedom to share and change the works. By contrast,
|
||||
the GNU General Public License is intended to guarantee your freedom to
|
||||
share and change all versions of a program--to make sure it remains free
|
||||
software for all its users. We, the Free Software Foundation, use the
|
||||
GNU General Public License for most of our software; it applies also to
|
||||
any other work released this way by its authors. You can apply it to
|
||||
your programs, too.
|
||||
|
||||
When we speak of free software, we are referring to freedom, not
|
||||
price. Our General Public Licenses are designed to make sure that you
|
||||
have the freedom to distribute copies of free software (and charge for
|
||||
them if you wish), that you receive source code or can get it if you
|
||||
want it, that you can change the software or use pieces of it in new
|
||||
free programs, and that you know you can do these things.
|
||||
|
||||
To protect your rights, we need to prevent others from denying you
|
||||
these rights or asking you to surrender the rights. Therefore, you have
|
||||
certain responsibilities if you distribute copies of the software, or if
|
||||
you modify it: responsibilities to respect the freedom of others.
|
||||
|
||||
For example, if you distribute copies of such a program, whether
|
||||
gratis or for a fee, you must pass on to the recipients the same
|
||||
freedoms that you received. You must make sure that they, too, receive
|
||||
or can get the source code. And you must show them these terms so they
|
||||
know their rights.
|
||||
|
||||
Developers that use the GNU GPL protect your rights with two steps:
|
||||
(1) assert copyright on the software, and (2) offer you this License
|
||||
giving you legal permission to copy, distribute and/or modify it.
|
||||
|
||||
For the developers' and authors' protection, the GPL clearly explains
|
||||
that there is no warranty for this free software. For both users' and
|
||||
authors' sake, the GPL requires that modified versions be marked as
|
||||
changed, so that their problems will not be attributed erroneously to
|
||||
authors of previous versions.
|
||||
|
||||
Some devices are designed to deny users access to install or run
|
||||
modified versions of the software inside them, although the manufacturer
|
||||
can do so. This is fundamentally incompatible with the aim of
|
||||
protecting users' freedom to change the software. The systematic
|
||||
pattern of such abuse occurs in the area of products for individuals to
|
||||
use, which is precisely where it is most unacceptable. Therefore, we
|
||||
have designed this version of the GPL to prohibit the practice for those
|
||||
products. If such problems arise substantially in other domains, we
|
||||
stand ready to extend this provision to those domains in future versions
|
||||
of the GPL, as needed to protect the freedom of users.
|
||||
|
||||
Finally, every program is threatened constantly by software patents.
|
||||
States should not allow patents to restrict development and use of
|
||||
software on general-purpose computers, but in those that do, we wish to
|
||||
avoid the special danger that patents applied to a free program could
|
||||
make it effectively proprietary. To prevent this, the GPL assures that
|
||||
patents cannot be used to render the program non-free.
|
||||
|
||||
The precise terms and conditions for copying, distribution and
|
||||
modification follow.
|
||||
|
||||
TERMS AND CONDITIONS
|
||||
|
||||
0. Definitions.
|
||||
|
||||
"This License" refers to version 3 of the GNU General Public License.
|
||||
|
||||
"Copyright" also means copyright-like laws that apply to other kinds of
|
||||
works, such as semiconductor masks.
|
||||
|
||||
"The Program" refers to any copyrightable work licensed under this
|
||||
License. Each licensee is addressed as "you". "Licensees" and
|
||||
"recipients" may be individuals or organizations.
|
||||
|
||||
To "modify" a work means to copy from or adapt all or part of the work
|
||||
in a fashion requiring copyright permission, other than the making of an
|
||||
exact copy. The resulting work is called a "modified version" of the
|
||||
earlier work or a work "based on" the earlier work.
|
||||
|
||||
A "covered work" means either the unmodified Program or a work based
|
||||
on the Program.
|
||||
|
||||
To "propagate" a work means to do anything with it that, without
|
||||
permission, would make you directly or secondarily liable for
|
||||
infringement under applicable copyright law, except executing it on a
|
||||
computer or modifying a private copy. Propagation includes copying,
|
||||
distribution (with or without modification), making available to the
|
||||
public, and in some countries other activities as well.
|
||||
|
||||
To "convey" a work means any kind of propagation that enables other
|
||||
parties to make or receive copies. Mere interaction with a user through
|
||||
a computer network, with no transfer of a copy, is not conveying.
|
||||
|
||||
An interactive user interface displays "Appropriate Legal Notices"
|
||||
to the extent that it includes a convenient and prominently visible
|
||||
feature that (1) displays an appropriate copyright notice, and (2)
|
||||
tells the user that there is no warranty for the work (except to the
|
||||
extent that warranties are provided), that licensees may convey the
|
||||
work under this License, and how to view a copy of this License. If
|
||||
the interface presents a list of user commands or options, such as a
|
||||
menu, a prominent item in the list meets this criterion.
|
||||
|
||||
1. Source Code.
|
||||
|
||||
The "source code" for a work means the preferred form of the work
|
||||
for making modifications to it. "Object code" means any non-source
|
||||
form of a work.
|
||||
|
||||
A "Standard Interface" means an interface that either is an official
|
||||
standard defined by a recognized standards body, or, in the case of
|
||||
interfaces specified for a particular programming language, one that
|
||||
is widely used among developers working in that language.
|
||||
|
||||
The "System Libraries" of an executable work include anything, other
|
||||
than the work as a whole, that (a) is included in the normal form of
|
||||
packaging a Major Component, but which is not part of that Major
|
||||
Component, and (b) serves only to enable use of the work with that
|
||||
Major Component, or to implement a Standard Interface for which an
|
||||
implementation is available to the public in source code form. A
|
||||
"Major Component", in this context, means a major essential component
|
||||
(kernel, window system, and so on) of the specific operating system
|
||||
(if any) on which the executable work runs, or a compiler used to
|
||||
produce the work, or an object code interpreter used to run it.
|
||||
|
||||
The "Corresponding Source" for a work in object code form means all
|
||||
the source code needed to generate, install, and (for an executable
|
||||
work) run the object code and to modify the work, including scripts to
|
||||
control those activities. However, it does not include the work's
|
||||
System Libraries, or general-purpose tools or generally available free
|
||||
programs which are used unmodified in performing those activities but
|
||||
which are not part of the work. For example, Corresponding Source
|
||||
includes interface definition files associated with source files for
|
||||
the work, and the source code for shared libraries and dynamically
|
||||
linked subprograms that the work is specifically designed to require,
|
||||
such as by intimate data communication or control flow between those
|
||||
subprograms and other parts of the work.
|
||||
|
||||
The Corresponding Source need not include anything that users
|
||||
can regenerate automatically from other parts of the Corresponding
|
||||
Source.
|
||||
|
||||
The Corresponding Source for a work in source code form is that
|
||||
same work.
|
||||
|
||||
2. Basic Permissions.
|
||||
|
||||
All rights granted under this License are granted for the term of
|
||||
copyright on the Program, and are irrevocable provided the stated
|
||||
conditions are met. This License explicitly affirms your unlimited
|
||||
permission to run the unmodified Program. The output from running a
|
||||
covered work is covered by this License only if the output, given its
|
||||
content, constitutes a covered work. This License acknowledges your
|
||||
rights of fair use or other equivalent, as provided by copyright law.
|
||||
|
||||
You may make, run and propagate covered works that you do not
|
||||
convey, without conditions so long as your license otherwise remains
|
||||
in force. You may convey covered works to others for the sole purpose
|
||||
of having them make modifications exclusively for you, or provide you
|
||||
with facilities for running those works, provided that you comply with
|
||||
the terms of this License in conveying all material for which you do
|
||||
not control copyright. Those thus making or running the covered works
|
||||
for you must do so exclusively on your behalf, under your direction
|
||||
and control, on terms that prohibit them from making any copies of
|
||||
your copyrighted material outside their relationship with you.
|
||||
|
||||
Conveying under any other circumstances is permitted solely under
|
||||
the conditions stated below. Sublicensing is not allowed; section 10
|
||||
makes it unnecessary.
|
||||
|
||||
3. Protecting Users' Legal Rights From Anti-Circumvention Law.
|
||||
|
||||
No covered work shall be deemed part of an effective technological
|
||||
measure under any applicable law fulfilling obligations under article
|
||||
11 of the WIPO copyright treaty adopted on 20 December 1996, or
|
||||
similar laws prohibiting or restricting circumvention of such
|
||||
measures.
|
||||
|
||||
When you convey a covered work, you waive any legal power to forbid
|
||||
circumvention of technological measures to the extent such circumvention
|
||||
is effected by exercising rights under this License with respect to
|
||||
the covered work, and you disclaim any intention to limit operation or
|
||||
modification of the work as a means of enforcing, against the work's
|
||||
users, your or third parties' legal rights to forbid circumvention of
|
||||
technological measures.
|
||||
|
||||
4. Conveying Verbatim Copies.
|
||||
|
||||
You may convey verbatim copies of the Program's source code as you
|
||||
receive it, in any medium, provided that you conspicuously and
|
||||
appropriately publish on each copy an appropriate copyright notice;
|
||||
keep intact all notices stating that this License and any
|
||||
non-permissive terms added in accord with section 7 apply to the code;
|
||||
keep intact all notices of the absence of any warranty; and give all
|
||||
recipients a copy of this License along with the Program.
|
||||
|
||||
You may charge any price or no price for each copy that you convey,
|
||||
and you may offer support or warranty protection for a fee.
|
||||
|
||||
5. Conveying Modified Source Versions.
|
||||
|
||||
You may convey a work based on the Program, or the modifications to
|
||||
produce it from the Program, in the form of source code under the
|
||||
terms of section 4, provided that you also meet all of these conditions:
|
||||
|
||||
a) The work must carry prominent notices stating that you modified
|
||||
it, and giving a relevant date.
|
||||
|
||||
b) The work must carry prominent notices stating that it is
|
||||
released under this License and any conditions added under section
|
||||
7. This requirement modifies the requirement in section 4 to
|
||||
"keep intact all notices".
|
||||
|
||||
c) You must license the entire work, as a whole, under this
|
||||
License to anyone who comes into possession of a copy. This
|
||||
License will therefore apply, along with any applicable section 7
|
||||
additional terms, to the whole of the work, and all its parts,
|
||||
regardless of how they are packaged. This License gives no
|
||||
permission to license the work in any other way, but it does not
|
||||
invalidate such permission if you have separately received it.
|
||||
|
||||
d) If the work has interactive user interfaces, each must display
|
||||
Appropriate Legal Notices; however, if the Program has interactive
|
||||
interfaces that do not display Appropriate Legal Notices, your
|
||||
work need not make them do so.
|
||||
|
||||
A compilation of a covered work with other separate and independent
|
||||
works, which are not by their nature extensions of the covered work,
|
||||
and which are not combined with it such as to form a larger program,
|
||||
in or on a volume of a storage or distribution medium, is called an
|
||||
"aggregate" if the compilation and its resulting copyright are not
|
||||
used to limit the access or legal rights of the compilation's users
|
||||
beyond what the individual works permit. Inclusion of a covered work
|
||||
in an aggregate does not cause this License to apply to the other
|
||||
parts of the aggregate.
|
||||
|
||||
6. Conveying Non-Source Forms.
|
||||
|
||||
You may convey a covered work in object code form under the terms
|
||||
of sections 4 and 5, provided that you also convey the
|
||||
machine-readable Corresponding Source under the terms of this License,
|
||||
in one of these ways:
|
||||
|
||||
a) Convey the object code in, or embodied in, a physical product
|
||||
(including a physical distribution medium), accompanied by the
|
||||
Corresponding Source fixed on a durable physical medium
|
||||
customarily used for software interchange.
|
||||
|
||||
b) Convey the object code in, or embodied in, a physical product
|
||||
(including a physical distribution medium), accompanied by a
|
||||
written offer, valid for at least three years and valid for as
|
||||
long as you offer spare parts or customer support for that product
|
||||
model, to give anyone who possesses the object code either (1) a
|
||||
copy of the Corresponding Source for all the software in the
|
||||
product that is covered by this License, on a durable physical
|
||||
medium customarily used for software interchange, for a price no
|
||||
more than your reasonable cost of physically performing this
|
||||
conveying of source, or (2) access to copy the
|
||||
Corresponding Source from a network server at no charge.
|
||||
|
||||
c) Convey individual copies of the object code with a copy of the
|
||||
written offer to provide the Corresponding Source. This
|
||||
alternative is allowed only occasionally and noncommercially, and
|
||||
only if you received the object code with such an offer, in accord
|
||||
with subsection 6b.
|
||||
|
||||
d) Convey the object code by offering access from a designated
|
||||
place (gratis or for a charge), and offer equivalent access to the
|
||||
Corresponding Source in the same way through the same place at no
|
||||
further charge. You need not require recipients to copy the
|
||||
Corresponding Source along with the object code. If the place to
|
||||
copy the object code is a network server, the Corresponding Source
|
||||
may be on a different server (operated by you or a third party)
|
||||
that supports equivalent copying facilities, provided you maintain
|
||||
clear directions next to the object code saying where to find the
|
||||
Corresponding Source. Regardless of what server hosts the
|
||||
Corresponding Source, you remain obligated to ensure that it is
|
||||
available for as long as needed to satisfy these requirements.
|
||||
|
||||
e) Convey the object code using peer-to-peer transmission, provided
|
||||
you inform other peers where the object code and Corresponding
|
||||
Source of the work are being offered to the general public at no
|
||||
charge under subsection 6d.
|
||||
|
||||
A separable portion of the object code, whose source code is excluded
|
||||
from the Corresponding Source as a System Library, need not be
|
||||
included in conveying the object code work.
|
||||
|
||||
A "User Product" is either (1) a "consumer product", which means any
|
||||
tangible personal property which is normally used for personal, family,
|
||||
or household purposes, or (2) anything designed or sold for incorporation
|
||||
into a dwelling. In determining whether a product is a consumer product,
|
||||
doubtful cases shall be resolved in favor of coverage. For a particular
|
||||
product received by a particular user, "normally used" refers to a
|
||||
typical or common use of that class of product, regardless of the status
|
||||
of the particular user or of the way in which the particular user
|
||||
actually uses, or expects or is expected to use, the product. A product
|
||||
is a consumer product regardless of whether the product has substantial
|
||||
commercial, industrial or non-consumer uses, unless such uses represent
|
||||
the only significant mode of use of the product.
|
||||
|
||||
"Installation Information" for a User Product means any methods,
|
||||
procedures, authorization keys, or other information required to install
|
||||
and execute modified versions of a covered work in that User Product from
|
||||
a modified version of its Corresponding Source. The information must
|
||||
suffice to ensure that the continued functioning of the modified object
|
||||
code is in no case prevented or interfered with solely because
|
||||
modification has been made.
|
||||
|
||||
If you convey an object code work under this section in, or with, or
|
||||
specifically for use in, a User Product, and the conveying occurs as
|
||||
part of a transaction in which the right of possession and use of the
|
||||
User Product is transferred to the recipient in perpetuity or for a
|
||||
fixed term (regardless of how the transaction is characterized), the
|
||||
Corresponding Source conveyed under this section must be accompanied
|
||||
by the Installation Information. But this requirement does not apply
|
||||
if neither you nor any third party retains the ability to install
|
||||
modified object code on the User Product (for example, the work has
|
||||
been installed in ROM).
|
||||
|
||||
The requirement to provide Installation Information does not include a
|
||||
requirement to continue to provide support service, warranty, or updates
|
||||
for a work that has been modified or installed by the recipient, or for
|
||||
the User Product in which it has been modified or installed. Access to a
|
||||
network may be denied when the modification itself materially and
|
||||
adversely affects the operation of the network or violates the rules and
|
||||
protocols for communication across the network.
|
||||
|
||||
Corresponding Source conveyed, and Installation Information provided,
|
||||
in accord with this section must be in a format that is publicly
|
||||
documented (and with an implementation available to the public in
|
||||
source code form), and must require no special password or key for
|
||||
unpacking, reading or copying.
|
||||
|
||||
7. Additional Terms.
|
||||
|
||||
"Additional permissions" are terms that supplement the terms of this
|
||||
License by making exceptions from one or more of its conditions.
|
||||
Additional permissions that are applicable to the entire Program shall
|
||||
be treated as though they were included in this License, to the extent
|
||||
that they are valid under applicable law. If additional permissions
|
||||
apply only to part of the Program, that part may be used separately
|
||||
under those permissions, but the entire Program remains governed by
|
||||
this License without regard to the additional permissions.
|
||||
|
||||
When you convey a copy of a covered work, you may at your option
|
||||
remove any additional permissions from that copy, or from any part of
|
||||
it. (Additional permissions may be written to require their own
|
||||
removal in certain cases when you modify the work.) You may place
|
||||
additional permissions on material, added by you to a covered work,
|
||||
for which you have or can give appropriate copyright permission.
|
||||
|
||||
Notwithstanding any other provision of this License, for material you
|
||||
add to a covered work, you may (if authorized by the copyright holders of
|
||||
that material) supplement the terms of this License with terms:
|
||||
|
||||
a) Disclaiming warranty or limiting liability differently from the
|
||||
terms of sections 15 and 16 of this License; or
|
||||
|
||||
b) Requiring preservation of specified reasonable legal notices or
|
||||
author attributions in that material or in the Appropriate Legal
|
||||
Notices displayed by works containing it; or
|
||||
|
||||
c) Prohibiting misrepresentation of the origin of that material, or
|
||||
requiring that modified versions of such material be marked in
|
||||
reasonable ways as different from the original version; or
|
||||
|
||||
d) Limiting the use for publicity purposes of names of licensors or
|
||||
authors of the material; or
|
||||
|
||||
e) Declining to grant rights under trademark law for use of some
|
||||
trade names, trademarks, or service marks; or
|
||||
|
||||
f) Requiring indemnification of licensors and authors of that
|
||||
material by anyone who conveys the material (or modified versions of
|
||||
it) with contractual assumptions of liability to the recipient, for
|
||||
any liability that these contractual assumptions directly impose on
|
||||
those licensors and authors.
|
||||
|
||||
All other non-permissive additional terms are considered "further
|
||||
restrictions" within the meaning of section 10. If the Program as you
|
||||
received it, or any part of it, contains a notice stating that it is
|
||||
governed by this License along with a term that is a further
|
||||
restriction, you may remove that term. If a license document contains
|
||||
a further restriction but permits relicensing or conveying under this
|
||||
License, you may add to a covered work material governed by the terms
|
||||
of that license document, provided that the further restriction does
|
||||
not survive such relicensing or conveying.
|
||||
|
||||
If you add terms to a covered work in accord with this section, you
|
||||
must place, in the relevant source files, a statement of the
|
||||
additional terms that apply to those files, or a notice indicating
|
||||
where to find the applicable terms.
|
||||
|
||||
Additional terms, permissive or non-permissive, may be stated in the
|
||||
form of a separately written license, or stated as exceptions;
|
||||
the above requirements apply either way.
|
||||
|
||||
8. Termination.
|
||||
|
||||
You may not propagate or modify a covered work except as expressly
|
||||
provided under this License. Any attempt otherwise to propagate or
|
||||
modify it is void, and will automatically terminate your rights under
|
||||
this License (including any patent licenses granted under the third
|
||||
paragraph of section 11).
|
||||
|
||||
However, if you cease all violation of this License, then your
|
||||
license from a particular copyright holder is reinstated (a)
|
||||
provisionally, unless and until the copyright holder explicitly and
|
||||
finally terminates your license, and (b) permanently, if the copyright
|
||||
holder fails to notify you of the violation by some reasonable means
|
||||
prior to 60 days after the cessation.
|
||||
|
||||
Moreover, your license from a particular copyright holder is
|
||||
reinstated permanently if the copyright holder notifies you of the
|
||||
violation by some reasonable means, this is the first time you have
|
||||
received notice of violation of this License (for any work) from that
|
||||
copyright holder, and you cure the violation prior to 30 days after
|
||||
your receipt of the notice.
|
||||
|
||||
Termination of your rights under this section does not terminate the
|
||||
licenses of parties who have received copies or rights from you under
|
||||
this License. If your rights have been terminated and not permanently
|
||||
reinstated, you do not qualify to receive new licenses for the same
|
||||
material under section 10.
|
||||
|
||||
9. Acceptance Not Required for Having Copies.
|
||||
|
||||
You are not required to accept this License in order to receive or
|
||||
run a copy of the Program. Ancillary propagation of a covered work
|
||||
occurring solely as a consequence of using peer-to-peer transmission
|
||||
to receive a copy likewise does not require acceptance. However,
|
||||
nothing other than this License grants you permission to propagate or
|
||||
modify any covered work. These actions infringe copyright if you do
|
||||
not accept this License. Therefore, by modifying or propagating a
|
||||
covered work, you indicate your acceptance of this License to do so.
|
||||
|
||||
10. Automatic Licensing of Downstream Recipients.
|
||||
|
||||
Each time you convey a covered work, the recipient automatically
|
||||
receives a license from the original licensors, to run, modify and
|
||||
propagate that work, subject to this License. You are not responsible
|
||||
for enforcing compliance by third parties with this License.
|
||||
|
||||
An "entity transaction" is a transaction transferring control of an
|
||||
organization, or substantially all assets of one, or subdividing an
|
||||
organization, or merging organizations. If propagation of a covered
|
||||
work results from an entity transaction, each party to that
|
||||
transaction who receives a copy of the work also receives whatever
|
||||
licenses to the work the party's predecessor in interest had or could
|
||||
give under the previous paragraph, plus a right to possession of the
|
||||
Corresponding Source of the work from the predecessor in interest, if
|
||||
the predecessor has it or can get it with reasonable efforts.
|
||||
|
||||
You may not impose any further restrictions on the exercise of the
|
||||
rights granted or affirmed under this License. For example, you may
|
||||
not impose a license fee, royalty, or other charge for exercise of
|
||||
rights granted under this License, and you may not initiate litigation
|
||||
(including a cross-claim or counterclaim in a lawsuit) alleging that
|
||||
any patent claim is infringed by making, using, selling, offering for
|
||||
sale, or importing the Program or any portion of it.
|
||||
|
||||
11. Patents.
|
||||
|
||||
A "contributor" is a copyright holder who authorizes use under this
|
||||
License of the Program or a work on which the Program is based. The
|
||||
work thus licensed is called the contributor's "contributor version".
|
||||
|
||||
A contributor's "essential patent claims" are all patent claims
|
||||
owned or controlled by the contributor, whether already acquired or
|
||||
hereafter acquired, that would be infringed by some manner, permitted
|
||||
by this License, of making, using, or selling its contributor version,
|
||||
but do not include claims that would be infringed only as a
|
||||
consequence of further modification of the contributor version. For
|
||||
purposes of this definition, "control" includes the right to grant
|
||||
patent sublicenses in a manner consistent with the requirements of
|
||||
this License.
|
||||
|
||||
Each contributor grants you a non-exclusive, worldwide, royalty-free
|
||||
patent license under the contributor's essential patent claims, to
|
||||
make, use, sell, offer for sale, import and otherwise run, modify and
|
||||
propagate the contents of its contributor version.
|
||||
|
||||
In the following three paragraphs, a "patent license" is any express
|
||||
agreement or commitment, however denominated, not to enforce a patent
|
||||
(such as an express permission to practice a patent or covenant not to
|
||||
sue for patent infringement). To "grant" such a patent license to a
|
||||
party means to make such an agreement or commitment not to enforce a
|
||||
patent against the party.
|
||||
|
||||
If you convey a covered work, knowingly relying on a patent license,
|
||||
and the Corresponding Source of the work is not available for anyone
|
||||
to copy, free of charge and under the terms of this License, through a
|
||||
publicly available network server or other readily accessible means,
|
||||
then you must either (1) cause the Corresponding Source to be so
|
||||
available, or (2) arrange to deprive yourself of the benefit of the
|
||||
patent license for this particular work, or (3) arrange, in a manner
|
||||
consistent with the requirements of this License, to extend the patent
|
||||
license to downstream recipients. "Knowingly relying" means you have
|
||||
actual knowledge that, but for the patent license, your conveying the
|
||||
covered work in a country, or your recipient's use of the covered work
|
||||
in a country, would infringe one or more identifiable patents in that
|
||||
country that you have reason to believe are valid.
|
||||
|
||||
If, pursuant to or in connection with a single transaction or
|
||||
arrangement, you convey, or propagate by procuring conveyance of, a
|
||||
covered work, and grant a patent license to some of the parties
|
||||
receiving the covered work authorizing them to use, propagate, modify
|
||||
or convey a specific copy of the covered work, then the patent license
|
||||
you grant is automatically extended to all recipients of the covered
|
||||
work and works based on it.
|
||||
|
||||
A patent license is "discriminatory" if it does not include within
|
||||
the scope of its coverage, prohibits the exercise of, or is
|
||||
conditioned on the non-exercise of one or more of the rights that are
|
||||
specifically granted under this License. You may not convey a covered
|
||||
work if you are a party to an arrangement with a third party that is
|
||||
in the business of distributing software, under which you make payment
|
||||
to the third party based on the extent of your activity of conveying
|
||||
the work, and under which the third party grants, to any of the
|
||||
parties who would receive the covered work from you, a discriminatory
|
||||
patent license (a) in connection with copies of the covered work
|
||||
conveyed by you (or copies made from those copies), or (b) primarily
|
||||
for and in connection with specific products or compilations that
|
||||
contain the covered work, unless you entered into that arrangement,
|
||||
or that patent license was granted, prior to 28 March 2007.
|
||||
|
||||
Nothing in this License shall be construed as excluding or limiting
|
||||
any implied license or other defenses to infringement that may
|
||||
otherwise be available to you under applicable patent law.
|
||||
|
||||
12. No Surrender of Others' Freedom.
|
||||
|
||||
If conditions are imposed on you (whether by court order, agreement or
|
||||
otherwise) that contradict the conditions of this License, they do not
|
||||
excuse you from the conditions of this License. If you cannot convey a
|
||||
covered work so as to satisfy simultaneously your obligations under this
|
||||
License and any other pertinent obligations, then as a consequence you may
|
||||
not convey it at all. For example, if you agree to terms that obligate you
|
||||
to collect a royalty for further conveying from those to whom you convey
|
||||
the Program, the only way you could satisfy both those terms and this
|
||||
License would be to refrain entirely from conveying the Program.
|
||||
|
||||
13. Use with the GNU Affero General Public License.
|
||||
|
||||
Notwithstanding any other provision of this License, you have
|
||||
permission to link or combine any covered work with a work licensed
|
||||
under version 3 of the GNU Affero General Public License into a single
|
||||
combined work, and to convey the resulting work. The terms of this
|
||||
License will continue to apply to the part which is the covered work,
|
||||
but the special requirements of the GNU Affero General Public License,
|
||||
section 13, concerning interaction through a network will apply to the
|
||||
combination as such.
|
||||
|
||||
14. Revised Versions of this License.
|
||||
|
||||
The Free Software Foundation may publish revised and/or new versions of
|
||||
the GNU General Public License from time to time. Such new versions will
|
||||
be similar in spirit to the present version, but may differ in detail to
|
||||
address new problems or concerns.
|
||||
|
||||
Each version is given a distinguishing version number. If the
|
||||
Program specifies that a certain numbered version of the GNU General
|
||||
Public License "or any later version" applies to it, you have the
|
||||
option of following the terms and conditions either of that numbered
|
||||
version or of any later version published by the Free Software
|
||||
Foundation. If the Program does not specify a version number of the
|
||||
GNU General Public License, you may choose any version ever published
|
||||
by the Free Software Foundation.
|
||||
|
||||
If the Program specifies that a proxy can decide which future
|
||||
versions of the GNU General Public License can be used, that proxy's
|
||||
public statement of acceptance of a version permanently authorizes you
|
||||
to choose that version for the Program.
|
||||
|
||||
Later license versions may give you additional or different
|
||||
permissions. However, no additional obligations are imposed on any
|
||||
author or copyright holder as a result of your choosing to follow a
|
||||
later version.
|
||||
|
||||
15. Disclaimer of Warranty.
|
||||
|
||||
THERE IS NO WARRANTY FOR THE PROGRAM, TO THE EXTENT PERMITTED BY
|
||||
APPLICABLE LAW. EXCEPT WHEN OTHERWISE STATED IN WRITING THE COPYRIGHT
|
||||
HOLDERS AND/OR OTHER PARTIES PROVIDE THE PROGRAM "AS IS" WITHOUT WARRANTY
|
||||
OF ANY KIND, EITHER EXPRESSED OR IMPLIED, INCLUDING, BUT NOT LIMITED TO,
|
||||
THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR
|
||||
PURPOSE. THE ENTIRE RISK AS TO THE QUALITY AND PERFORMANCE OF THE PROGRAM
|
||||
IS WITH YOU. SHOULD THE PROGRAM PROVE DEFECTIVE, YOU ASSUME THE COST OF
|
||||
ALL NECESSARY SERVICING, REPAIR OR CORRECTION.
|
||||
|
||||
16. Limitation of Liability.
|
||||
|
||||
IN NO EVENT UNLESS REQUIRED BY APPLICABLE LAW OR AGREED TO IN WRITING
|
||||
WILL ANY COPYRIGHT HOLDER, OR ANY OTHER PARTY WHO MODIFIES AND/OR CONVEYS
|
||||
THE PROGRAM AS PERMITTED ABOVE, BE LIABLE TO YOU FOR DAMAGES, INCLUDING ANY
|
||||
GENERAL, SPECIAL, INCIDENTAL OR CONSEQUENTIAL DAMAGES ARISING OUT OF THE
|
||||
USE OR INABILITY TO USE THE PROGRAM (INCLUDING BUT NOT LIMITED TO LOSS OF
|
||||
DATA OR DATA BEING RENDERED INACCURATE OR LOSSES SUSTAINED BY YOU OR THIRD
|
||||
PARTIES OR A FAILURE OF THE PROGRAM TO OPERATE WITH ANY OTHER PROGRAMS),
|
||||
EVEN IF SUCH HOLDER OR OTHER PARTY HAS BEEN ADVISED OF THE POSSIBILITY OF
|
||||
SUCH DAMAGES.
|
||||
|
||||
17. Interpretation of Sections 15 and 16.
|
||||
|
||||
If the disclaimer of warranty and limitation of liability provided
|
||||
above cannot be given local legal effect according to their terms,
|
||||
reviewing courts shall apply local law that most closely approximates
|
||||
an absolute waiver of all civil liability in connection with the
|
||||
Program, unless a warranty or assumption of liability accompanies a
|
||||
copy of the Program in return for a fee.
|
||||
|
||||
END OF TERMS AND CONDITIONS
|
||||
|
||||
How to Apply These Terms to Your New Programs
|
||||
|
||||
If you develop a new program, and you want it to be of the greatest
|
||||
possible use to the public, the best way to achieve this is to make it
|
||||
free software which everyone can redistribute and change under these terms.
|
||||
|
||||
To do so, attach the following notices to the program. It is safest
|
||||
to attach them to the start of each source file to most effectively
|
||||
state the exclusion of warranty; and each file should have at least
|
||||
the "copyright" line and a pointer to where the full notice is found.
|
||||
|
||||
<one line to give the program's name and a brief idea of what it does.>
|
||||
Copyright (C) <year> <name of author>
|
||||
|
||||
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, see <http://www.gnu.org/licenses/>.
|
||||
|
||||
Also add information on how to contact you by electronic and paper mail.
|
||||
|
||||
If the program does terminal interaction, make it output a short
|
||||
notice like this when it starts in an interactive mode:
|
||||
|
||||
<program> Copyright (C) <year> <name of author>
|
||||
This program comes with ABSOLUTELY NO WARRANTY; for details type `show w'.
|
||||
This is free software, and you are welcome to redistribute it
|
||||
under certain conditions; type `show c' for details.
|
||||
|
||||
The hypothetical commands `show w' and `show c' should show the appropriate
|
||||
parts of the General Public License. Of course, your program's commands
|
||||
might be different; for a GUI interface, you would use an "about box".
|
||||
|
||||
You should also get your employer (if you work as a programmer) or school,
|
||||
if any, to sign a "copyright disclaimer" for the program, if necessary.
|
||||
For more information on this, and how to apply and follow the GNU GPL, see
|
||||
<http://www.gnu.org/licenses/>.
|
||||
|
||||
The GNU General Public License does not permit incorporating your program
|
||||
into proprietary programs. If your program is a subroutine library, you
|
||||
may consider it more useful to permit linking proprietary applications with
|
||||
the library. If this is what you want to do, use the GNU Lesser General
|
||||
Public License instead of this License. But first, please read
|
||||
<http://www.gnu.org/philosophy/why-not-lgpl.html>.
|
207
flight/Libraries/rscode/rs.c
Normal file
207
flight/Libraries/rscode/rs.c
Normal file
@ -0,0 +1,207 @@
|
||||
/*
|
||||
* Reed Solomon Encoder/Decoder
|
||||
*
|
||||
* Copyright Henry Minsky (hqm@alum.mit.edu) 1991-2009
|
||||
*
|
||||
* This software library is licensed under terms of the GNU GENERAL
|
||||
* PUBLIC LICENSE
|
||||
*
|
||||
* RSCODE 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.
|
||||
*
|
||||
* RSCODE 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 Rscode. If not, see <http://www.gnu.org/licenses/>.
|
||||
|
||||
* Commercial licensing is available under a separate license, please
|
||||
* contact author for details.
|
||||
*
|
||||
* Source code is available at http://rscode.sourceforge.net
|
||||
*/
|
||||
|
||||
#include <stdio.h>
|
||||
#include <ctype.h>
|
||||
#include "ecc.h"
|
||||
|
||||
/* Encoder parity bytes */
|
||||
int pBytes[MAXDEG];
|
||||
|
||||
/* Decoder syndrome bytes */
|
||||
int synBytes[MAXDEG];
|
||||
|
||||
/* generator polynomial */
|
||||
int genPoly[MAXDEG*2];
|
||||
|
||||
int DEBUG = FALSE;
|
||||
|
||||
static void
|
||||
compute_genpoly (int nbytes, int genpoly[]);
|
||||
|
||||
/* Initialize lookup tables, polynomials, etc. */
|
||||
void
|
||||
initialize_ecc ()
|
||||
{
|
||||
/* Initialize the galois field arithmetic tables */
|
||||
init_galois_tables();
|
||||
|
||||
/* Compute the encoder generator polynomial */
|
||||
compute_genpoly(RS_ECC_NPARITY, genPoly);
|
||||
}
|
||||
|
||||
void
|
||||
zero_fill_from (unsigned char buf[], int from, int to)
|
||||
{
|
||||
int i;
|
||||
for (i = from; i < to; i++) buf[i] = 0;
|
||||
}
|
||||
|
||||
/* debugging routines */
|
||||
void
|
||||
print_parity (void)
|
||||
{
|
||||
#ifdef NEVER
|
||||
int i;
|
||||
printf("Parity Bytes: ");
|
||||
for (i = 0; i < RS_ECC_NPARITY; i++)
|
||||
printf("[%d]:%x, ",i,pBytes[i]);
|
||||
printf("\n");
|
||||
#endif
|
||||
}
|
||||
|
||||
|
||||
void
|
||||
print_syndrome (void)
|
||||
{
|
||||
#ifdef NEVER
|
||||
int i;
|
||||
printf("Syndrome Bytes: ");
|
||||
for (i = 0; i < RS_ECC_NPARITY; i++)
|
||||
printf("[%d]:%x, ",i,synBytes[i]);
|
||||
printf("\n");
|
||||
#endif
|
||||
}
|
||||
|
||||
/* Append the parity bytes onto the end of the message */
|
||||
void
|
||||
build_codeword (unsigned char msg[], int nbytes, unsigned char dst[])
|
||||
{
|
||||
int i;
|
||||
|
||||
for (i = 0; i < nbytes; i++) dst[i] = msg[i];
|
||||
|
||||
for (i = 0; i < RS_ECC_NPARITY; i++) {
|
||||
dst[i+nbytes] = pBytes[RS_ECC_NPARITY-1-i];
|
||||
}
|
||||
}
|
||||
|
||||
/**********************************************************
|
||||
* Reed Solomon Decoder
|
||||
*
|
||||
* Computes the syndrome of a codeword. Puts the results
|
||||
* into the synBytes[] array.
|
||||
*/
|
||||
|
||||
void
|
||||
decode_data(unsigned char data[], int nbytes)
|
||||
{
|
||||
int i, j, sum;
|
||||
for (j = 0; j < RS_ECC_NPARITY; j++) {
|
||||
sum = 0;
|
||||
for (i = 0; i < nbytes; i++) {
|
||||
sum = data[i] ^ gmult(gexp[j+1], sum);
|
||||
}
|
||||
synBytes[j] = sum;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
/* Check if the syndrome is zero */
|
||||
int
|
||||
check_syndrome (void)
|
||||
{
|
||||
int i, nz = 0;
|
||||
for (i =0 ; i < RS_ECC_NPARITY; i++) {
|
||||
if (synBytes[i] != 0) {
|
||||
nz = 1;
|
||||
break;
|
||||
}
|
||||
}
|
||||
return nz;
|
||||
}
|
||||
|
||||
|
||||
void
|
||||
debug_check_syndrome (void)
|
||||
{
|
||||
#ifdef NEVER
|
||||
int i;
|
||||
|
||||
for (i = 0; i < 3; i++) {
|
||||
printf(" inv log S[%d]/S[%d] = %d\n", i, i+1,
|
||||
glog[gmult(synBytes[i], ginv(synBytes[i+1]))]);
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
|
||||
/* Create a generator polynomial for an n byte RS code.
|
||||
* The coefficients are returned in the genPoly arg.
|
||||
* Make sure that the genPoly array which is passed in is
|
||||
* at least n+1 bytes long.
|
||||
*/
|
||||
|
||||
static void
|
||||
compute_genpoly (int nbytes, int genpoly[])
|
||||
{
|
||||
int i, tp[256], tp1[256];
|
||||
|
||||
/* multiply (x + a^n) for n = 1 to nbytes */
|
||||
|
||||
zero_poly(tp1);
|
||||
tp1[0] = 1;
|
||||
|
||||
for (i = 1; i <= nbytes; i++) {
|
||||
zero_poly(tp);
|
||||
tp[0] = gexp[i]; /* set up x+a^n */
|
||||
tp[1] = 1;
|
||||
|
||||
mult_polys(genpoly, tp, tp1);
|
||||
copy_poly(tp1, genpoly);
|
||||
}
|
||||
}
|
||||
|
||||
/* Simulate a LFSR with generator polynomial for n byte RS code.
|
||||
* Pass in a pointer to the data array, and amount of data.
|
||||
*
|
||||
* The parity bytes are deposited into pBytes[], and the whole message
|
||||
* and parity are copied to dest to make a codeword.
|
||||
*
|
||||
*/
|
||||
|
||||
void
|
||||
encode_data (unsigned char msg[], int nbytes, unsigned char dst[])
|
||||
{
|
||||
int i, LFSR[RS_ECC_NPARITY+1],dbyte, j;
|
||||
|
||||
for(i=0; i < RS_ECC_NPARITY+1; i++) LFSR[i]=0;
|
||||
|
||||
for (i = 0; i < nbytes; i++) {
|
||||
dbyte = msg[i] ^ LFSR[RS_ECC_NPARITY-1];
|
||||
for (j = RS_ECC_NPARITY-1; j > 0; j--) {
|
||||
LFSR[j] = LFSR[j-1] ^ gmult(genPoly[j], dbyte);
|
||||
}
|
||||
LFSR[0] = gmult(genPoly[0], dbyte);
|
||||
}
|
||||
|
||||
for (i = 0; i < RS_ECC_NPARITY; i++)
|
||||
pBytes[i] = LFSR[i];
|
||||
|
||||
build_codeword(msg, nbytes, dst);
|
||||
}
|
||||
|
86
flight/Libraries/rscode/rs.doc
Normal file
86
flight/Libraries/rscode/rs.doc
Normal file
@ -0,0 +1,86 @@
|
||||
|
||||
|
||||
Introduction to Reed Solomon Codes:
|
||||
|
||||
Henry Minsky, Universal Access Inc.
|
||||
hqm@alum.mit.edu
|
||||
|
||||
[For details see Cain, Clark, "Error-Correction Coding For Digital
|
||||
Communications", pp. 205.] The Reed-Solomon Code is an algebraic code
|
||||
belonging to the class of BCH (Bose-Chaudry-Hocquehen) multiple burst
|
||||
correcting cyclic codes. The Reed Solomon code operates on bytes of
|
||||
fixed length.
|
||||
|
||||
Given m parity bytes, a Reed-Solomon code can correct up to m byte
|
||||
errors in known positions (erasures), or detect and correct up to m/2
|
||||
byte errors in unknown positions.
|
||||
|
||||
This is an implementation of a Reed-Solomon code with 8 bit bytes, and
|
||||
a configurable number of parity bytes. The maximum sequence length
|
||||
(codeword) that can be generated is 255 bytes, including parity bytes.
|
||||
In practice, shorter sequences are used.
|
||||
|
||||
ENCODING: The basic principle of encoding is to find the remainder of
|
||||
the message divided by a generator polynomial G(x). The encoder works
|
||||
by simulating a Linear Feedback Shift Register with degree equal to
|
||||
G(x), and feedback taps with the coefficents of the generating
|
||||
polynomial of the code.
|
||||
|
||||
The rs.c file contains an algorithm to generate the encoder polynomial
|
||||
for any number of bytes of parity, configurable as the NPAR constant
|
||||
in the file ecc.h.
|
||||
|
||||
For this RS code, G(x) = (x-a^1)(x-a^2)(x-a^3)(x-a^4)...(x-a^NPAR)
|
||||
where 'a' is a primitive element of the Galois Field GF(256) (== 2).
|
||||
|
||||
DECODING
|
||||
|
||||
The decoder generates four syndrome bytes, which will be all zero if
|
||||
the message has no errors. If there are errors, the location and value
|
||||
of the errors can be determined in a number of ways.
|
||||
|
||||
Computing the syndromes is easily done as a sum of products, see pp.
|
||||
179 [Rhee 89].
|
||||
|
||||
Fundamentally, the syndome bytes form four simultaneous equations
|
||||
which can be solved to find the error locations. Once error locations
|
||||
are known, the syndrome bytes can be used to find the value of the
|
||||
errors, and they can thus be corrected.
|
||||
|
||||
A simplified solution for locating and correcting single errors is
|
||||
given in Cain and Clark, Ch. 5.
|
||||
|
||||
The more general error-location algorithm is the Berlekamp-Massey
|
||||
algorithm, which will locate up to four errors, by iteratively solving
|
||||
for the error-locator polynomial. The Modified Berlekamp Massey
|
||||
algorithm takes as initial conditions any known suspicious bytes
|
||||
(erasure flags) which you may have (such as might be flagged by
|
||||
a laser demodulator, or deduced from a failure in a cross-interleaved
|
||||
block code row or column).
|
||||
|
||||
Once the location of errors is known, error correction is done using
|
||||
the error-evaluator polynomial.
|
||||
|
||||
APPLICATION IDEAS
|
||||
|
||||
As an example application, this library could be used to implement the
|
||||
Compact Disc standard of 24 data bytes and 4 parity bytes. A RS code
|
||||
with 24 data bytes and 4 parity bytes is referred to as a (28,24) RS
|
||||
code. A (n, k) RS code is said to have efficiency k/n. This first
|
||||
(28,24) coding is called the C2 or level 2 encoding, because in a
|
||||
doubly encoded scheme, the codewords are decoded at the second
|
||||
decoding step.
|
||||
|
||||
In following the approach used by Compact Disc digital audio, the 28
|
||||
byte C2 codewords are four way interleaved and then the interleaved
|
||||
data is encoded again with a (32,28) RS code. The is the C1 encoding
|
||||
stage. This produces what is known as a "product code", and has
|
||||
excellent error correction capability due to the imposition of
|
||||
two-dimensional structure on the parity checks. The interleave helps
|
||||
to insure against the case that a multibyte burst error wipes out more
|
||||
than two bytes in each codeword. The cross-correction capability of
|
||||
the product code can provide backup if in fact there are more than 2
|
||||
uncorrectable errors in a block.
|
||||
|
||||
|
||||
|
@ -1,9 +1,14 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup OpenPilotModules OpenPilot Modules
|
||||
* @{
|
||||
* @addtogroup PipXtremeModule PipXtreme Module
|
||||
* @{
|
||||
*
|
||||
* @file pipxtrememod.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @brief The PipXtreme system module
|
||||
*
|
||||
* @file watchdog.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @brief RF Module hardware layer
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
*
|
||||
*****************************************************************************/
|
||||
@ -22,11 +27,9 @@
|
||||
* with this program; if not, write to the Free Software Foundation, Inc.,
|
||||
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
*/
|
||||
#ifndef PIPXTREMEMOD_H
|
||||
#define PIPXTREMEMOD_H
|
||||
|
||||
#ifndef _WATCHDOG_H_
|
||||
#define _WATCHDOG_H_
|
||||
int32_t PipXtremeModInitialize(void);
|
||||
|
||||
uint16_t watchdog_Init(uint16_t delayMs);
|
||||
void watchdog_Clear(void);
|
||||
|
||||
#endif
|
||||
#endif // PIPXTREMEMOD_H
|
201
flight/Modules/PipXtreme/pipxtrememod.c
Normal file
201
flight/Modules/PipXtreme/pipxtrememod.c
Normal file
@ -0,0 +1,201 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup OpenPilotModules OpenPilot Modules
|
||||
* @brief The OpenPilot Modules do the majority of the control in OpenPilot. The
|
||||
* @ref PipXtremeModule The PipXtreme Module is the equivalanet of the System
|
||||
* Module for the PipXtreme modem. it starts all the other modules.
|
||||
# This is done through the @ref PIOS "PIOS Hardware abstraction layer",
|
||||
# which then contains hardware specific implementations
|
||||
* (currently only STM32 supported)
|
||||
*
|
||||
* @{
|
||||
* @addtogroup PipXtremeModule PipXtreme Module
|
||||
* @brief Initializes PIOS and other modules runs monitoring
|
||||
* After initializing all the modules runs basic monitoring and
|
||||
* alarms.
|
||||
* @{
|
||||
*
|
||||
* @file pipxtrememod.c
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @brief System module
|
||||
*
|
||||
* @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 <pipxstatus.h>
|
||||
#include <pios_board_info.h>
|
||||
#include "systemmod.h"
|
||||
|
||||
// Private constants
|
||||
#define SYSTEM_UPDATE_PERIOD_MS 1000
|
||||
#define LED_BLINK_RATE_HZ 5
|
||||
|
||||
#if defined(PIOS_SYSTEM_STACK_SIZE)
|
||||
#define STACK_SIZE_BYTES PIOS_SYSTEM_STACK_SIZE
|
||||
#else
|
||||
#define STACK_SIZE_BYTES 924
|
||||
#endif
|
||||
|
||||
#define TASK_PRIORITY (tskIDLE_PRIORITY+2)
|
||||
|
||||
// Private types
|
||||
|
||||
// Private variables
|
||||
static uint32_t idleCounter;
|
||||
static uint32_t idleCounterClear;
|
||||
static xTaskHandle systemTaskHandle;
|
||||
static bool stackOverflow;
|
||||
static bool mallocFailed;
|
||||
|
||||
// Private functions
|
||||
static void systemTask(void *parameters);
|
||||
|
||||
/**
|
||||
* Create the module task.
|
||||
* \returns 0 on success or -1 if initialization failed
|
||||
*/
|
||||
int32_t PipXtremeModStart(void)
|
||||
{
|
||||
// Initialize vars
|
||||
stackOverflow = false;
|
||||
mallocFailed = false;
|
||||
// Create pipxtreme system task
|
||||
xTaskCreate(systemTask, (signed char *)"PipXtreme", STACK_SIZE_BYTES/4, NULL, TASK_PRIORITY, &systemTaskHandle);
|
||||
// Register task
|
||||
TaskMonitorAdd(TASKINFO_RUNNING_SYSTEM, systemTaskHandle);
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* Initialize the module, called on startup.
|
||||
* \returns 0 on success or -1 if initialization failed
|
||||
*/
|
||||
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);
|
||||
|
||||
// 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;
|
||||
|
||||
// Update the object
|
||||
PipXStatusSet(&pipxStatus);
|
||||
|
||||
// Call the module start function.
|
||||
PipXtremeModStart();
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
MODULE_INITCALL(PipXtremeModInitialize, 0)
|
||||
|
||||
/**
|
||||
* System task, periodically executes every SYSTEM_UPDATE_PERIOD_MS
|
||||
*/
|
||||
static void systemTask(void *parameters)
|
||||
{
|
||||
portTickType lastSysTime;
|
||||
|
||||
/* create all modules thread */
|
||||
MODULE_TASKCREATE_ALL;
|
||||
|
||||
if (mallocFailed) {
|
||||
/* We failed to malloc during task creation,
|
||||
* system behaviour is undefined. Reset and let
|
||||
* the BootFault code recover for us.
|
||||
*/
|
||||
PIOS_SYS_Reset();
|
||||
}
|
||||
|
||||
// Initialize vars
|
||||
idleCounter = 0;
|
||||
idleCounterClear = 0;
|
||||
lastSysTime = xTaskGetTickCount();
|
||||
|
||||
// Main system loop
|
||||
while (1) {
|
||||
|
||||
// Flash the heartbeat LED
|
||||
#if defined(PIOS_LED_HEARTBEAT)
|
||||
PIOS_LED_Toggle(PIOS_LED_HEARTBEAT);
|
||||
#endif /* PIOS_LED_HEARTBEAT */
|
||||
|
||||
// Wait until next period
|
||||
vTaskDelayUntil(&lastSysTime, SYSTEM_UPDATE_PERIOD_MS / portTICK_RATE_MS);
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Called by the RTOS when the CPU is idle, used to measure the CPU idle time.
|
||||
*/
|
||||
void vApplicationIdleHook(void)
|
||||
{
|
||||
// Called when the scheduler has no tasks to run
|
||||
if (idleCounterClear == 0) {
|
||||
++idleCounter;
|
||||
} else {
|
||||
idleCounter = 0;
|
||||
idleCounterClear = 0;
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Called by the RTOS when a stack overflow is detected.
|
||||
*/
|
||||
#define DEBUG_STACK_OVERFLOW 0
|
||||
void vApplicationStackOverflowHook(xTaskHandle * pxTask, signed portCHAR * pcTaskName)
|
||||
{
|
||||
stackOverflow = true;
|
||||
#if DEBUG_STACK_OVERFLOW
|
||||
static volatile bool wait_here = true;
|
||||
while(wait_here);
|
||||
wait_here = true;
|
||||
#endif
|
||||
}
|
||||
|
||||
/**
|
||||
* Called by the RTOS when a malloc call fails.
|
||||
*/
|
||||
#define DEBUG_MALLOC_FAILURES 0
|
||||
void vApplicationMallocFailedHook(void)
|
||||
{
|
||||
mallocFailed = true;
|
||||
#if DEBUG_MALLOC_FAILURES
|
||||
static volatile bool wait_here = true;
|
||||
while(wait_here);
|
||||
wait_here = true;
|
||||
#endif
|
||||
}
|
||||
|
||||
/**
|
||||
* @}
|
||||
* @}
|
||||
*/
|
1069
flight/Modules/RadioComBridge/RadioComBridge.c
Normal file
1069
flight/Modules/RadioComBridge/RadioComBridge.c
Normal file
@ -0,0 +1,1069 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup OpenPilotModules OpenPilot Modules
|
||||
* @{
|
||||
* @addtogroup RadioComBridgeModule Com Port to Radio Bridge Module
|
||||
* @brief Bridge Com and Radio ports
|
||||
* @{
|
||||
*
|
||||
* @file RadioComBridge.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 <openpilot.h>
|
||||
#include <radiocombridge.h>
|
||||
#include <packet_handler.h>
|
||||
#include <gcsreceiver.h>
|
||||
#include <pipxstatus.h>
|
||||
#include <objectpersistence.h>
|
||||
#include <pipxsettings.h>
|
||||
#include <uavtalk_priv.h>
|
||||
#include <pios_rfm22b.h>
|
||||
#include <ecc.h>
|
||||
#if defined(PIOS_INCLUDE_FLASH_EEPROM)
|
||||
#include <pios_eeprom.h>
|
||||
#endif
|
||||
|
||||
#include <stdbool.h>
|
||||
|
||||
// ****************
|
||||
// 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 2000
|
||||
#define RADIOSTATS_UPDATE_PERIOD_MS 1000
|
||||
#define MAX_LOST_CONTACT_TIME 4
|
||||
#define PACKET_QUEUE_SIZE 10
|
||||
#define MAX_PORT_DELAY 200
|
||||
#define EV_PACKET_RECEIVED 0x20
|
||||
#define EV_SEND_ACK 0x40
|
||||
#define EV_SEND_NACK 0x80
|
||||
|
||||
// ****************
|
||||
// Private types
|
||||
|
||||
typedef struct {
|
||||
uint32_t pairID;
|
||||
uint16_t retries;
|
||||
uint16_t errors;
|
||||
uint16_t uavtalk_errors;
|
||||
uint16_t resets;
|
||||
int8_t rssi;
|
||||
uint8_t lastContact;
|
||||
} PairStats;
|
||||
|
||||
typedef struct {
|
||||
// The task handles.
|
||||
xTaskHandle comUAVTalkTaskHandle;
|
||||
xTaskHandle radioReceiveTaskHandle;
|
||||
xTaskHandle sendPacketTaskHandle;
|
||||
xTaskHandle sendDataTaskHandle;
|
||||
xTaskHandle radioStatusTaskHandle;
|
||||
xTaskHandle transparentCommTaskHandle;
|
||||
xTaskHandle ppmInputTaskHandle;
|
||||
|
||||
// The UAVTalk connection on the com side.
|
||||
UAVTalkConnection inUAVTalkCon;
|
||||
UAVTalkConnection outUAVTalkCon;
|
||||
|
||||
// Queue handles.
|
||||
xQueueHandle sendPacketQueue;
|
||||
xQueueHandle objEventQueue;
|
||||
|
||||
// Error statistics.
|
||||
uint32_t comTxErrors;
|
||||
uint32_t comTxRetries;
|
||||
uint32_t comRxErrors;
|
||||
uint32_t radioTxErrors;
|
||||
uint32_t radioTxRetries;
|
||||
uint32_t radioRxErrors;
|
||||
uint32_t UAVTalkErrors;
|
||||
uint32_t packetErrors;
|
||||
uint16_t txBytes;
|
||||
uint16_t rxBytes;
|
||||
|
||||
// The destination ID
|
||||
uint32_t destination_id;
|
||||
|
||||
// The packet timeout.
|
||||
portTickType send_timeout;
|
||||
uint16_t min_packet_size;
|
||||
|
||||
// Track other radios that are in range.
|
||||
PairStats pairStats[PIPXSTATUS_PAIRIDS_NUMELEM];
|
||||
|
||||
} 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 comUAVTalkTask(void *parameters);
|
||||
static void radioReceiveTask(void *parameters);
|
||||
static void sendPacketTask(void *parameters);
|
||||
static void sendDataTask(void *parameters);
|
||||
static void transparentCommTask(void * parameters);
|
||||
static void radioStatusTask(void *parameters);
|
||||
static void ppmInputTask(void *parameters);
|
||||
static int32_t transmitData(uint8_t * data, int32_t length);
|
||||
static int32_t transmitPacket(PHPacketHandle packet);
|
||||
static void receiveData(uint8_t *buf, uint8_t len);
|
||||
static void StatusHandler(PHStatusPacketHandle p);
|
||||
static void PPMHandler(uint16_t *channels);
|
||||
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 updateSettings();
|
||||
|
||||
// ****************
|
||||
// Private variables
|
||||
|
||||
static RadioComBridgeData *data;
|
||||
|
||||
/**
|
||||
* Start the module
|
||||
* \return -1 if initialisation failed
|
||||
* \return 0 on success
|
||||
*/
|
||||
static int32_t RadioComBridgeStart(void)
|
||||
{
|
||||
if(data) {
|
||||
// Start the tasks
|
||||
xTaskCreate(comUAVTalkTask, (signed char *)"ComUAVTalk", STACK_SIZE_BYTES, NULL, TASK_PRIORITY + 2, &(data->comUAVTalkTaskHandle));
|
||||
if(PIOS_COM_TRANS_COM)
|
||||
xTaskCreate(transparentCommTask, (signed char *)"transparentComm", STACK_SIZE_BYTES, NULL, TASK_PRIORITY + 2, &(data->transparentCommTaskHandle));
|
||||
xTaskCreate(radioReceiveTask, (signed char *)"RadioReceive", STACK_SIZE_BYTES, NULL, TASK_PRIORITY+ 2, &(data->radioReceiveTaskHandle));
|
||||
xTaskCreate(sendPacketTask, (signed char *)"SendPacketTask", STACK_SIZE_BYTES, NULL, TASK_PRIORITY + 2, &(data->sendPacketTaskHandle));
|
||||
xTaskCreate(sendDataTask, (signed char *)"SendDataTask", STACK_SIZE_BYTES, NULL, TASK_PRIORITY+ 2, &(data->sendDataTaskHandle));
|
||||
xTaskCreate(radioStatusTask, (signed char *)"RadioStatus", STACK_SIZE_BYTES, NULL, TASK_PRIORITY, &(data->radioStatusTaskHandle));
|
||||
if(PIOS_PPM_RECEIVER)
|
||||
xTaskCreate(ppmInputTask, (signed char *)"PPMInputTask", STACK_SIZE_BYTES, NULL, TASK_PRIORITY + 2, &(data->ppmInputTaskHandle));
|
||||
#ifdef PIOS_INCLUDE_WDG
|
||||
PIOS_WDG_RegisterFlag(PIOS_WDG_COMUAVTALK);
|
||||
if(PIOS_COM_TRANS_COM)
|
||||
PIOS_WDG_RegisterFlag(PIOS_WDG_TRANSCOMM);
|
||||
PIOS_WDG_RegisterFlag(PIOS_WDG_RADIORECEIVE);
|
||||
PIOS_WDG_RegisterFlag(PIOS_WDG_SENDPACKET);
|
||||
//PIOS_WDG_RegisterFlag(PIOS_WDG_SENDDATA);
|
||||
if(PIOS_PPM_RECEIVER)
|
||||
PIOS_WDG_RegisterFlag(PIOS_WDG_PPMINPUT);
|
||||
#endif
|
||||
return 0;
|
||||
}
|
||||
|
||||
return -1;
|
||||
}
|
||||
|
||||
/**
|
||||
* Initialise the module
|
||||
* \return -1 if initialisation failed
|
||||
* \return 0 on success
|
||||
*/
|
||||
static int32_t RadioComBridgeInitialize(void)
|
||||
{
|
||||
|
||||
// allocate and initialize the static data storage only if module is enabled
|
||||
data = (RadioComBridgeData *)pvPortMalloc(sizeof(RadioComBridgeData));
|
||||
if (!data)
|
||||
return -1;
|
||||
|
||||
// Initialize the UAVObjects that we use
|
||||
GCSReceiverInitialize();
|
||||
PipXStatusInitialize();
|
||||
ObjectPersistenceInitialize();
|
||||
updateSettings();
|
||||
|
||||
// Initialise UAVTalk
|
||||
data->inUAVTalkCon = UAVTalkInitialize(0);
|
||||
data->outUAVTalkCon = UAVTalkInitialize(&transmitData);
|
||||
|
||||
// Initialize the queues.
|
||||
data->sendPacketQueue = xQueueCreate(PACKET_QUEUE_SIZE, sizeof(PHPacketHandle));
|
||||
data->objEventQueue = xQueueCreate(PACKET_QUEUE_SIZE, sizeof(UAVObjEvent));
|
||||
|
||||
// Initialize the statistics.
|
||||
data->radioTxErrors = 0;
|
||||
data->radioTxRetries = 0;
|
||||
data->radioRxErrors = 0;
|
||||
data->comTxErrors = 0;
|
||||
data->comTxRetries = 0;
|
||||
data->comRxErrors = 0;
|
||||
data->UAVTalkErrors = 0;
|
||||
data->packetErrors = 0;
|
||||
|
||||
// Register the callbacks with the packet handler
|
||||
PHRegisterOutputStream(pios_packet_handler, transmitPacket);
|
||||
PHRegisterDataHandler(pios_packet_handler, receiveData);
|
||||
PHRegisterStatusHandler(pios_packet_handler, StatusHandler);
|
||||
PHRegisterPPMHandler(pios_packet_handler, PPMHandler);
|
||||
|
||||
// Initialize the packet send timeout
|
||||
data->send_timeout = 25; // ms
|
||||
data->min_packet_size = 50;
|
||||
|
||||
// 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].lastContact = 0;
|
||||
}
|
||||
// The first slot is reserved for our current pairID
|
||||
PipXSettingsPairIDGet(&(data->pairStats[0].pairID));
|
||||
|
||||
// Configure our UAVObjects for updates.
|
||||
UAVObjConnectQueue(UAVObjGetByName("PipXStatus"), data->objEventQueue, EV_UPDATED | EV_UPDATED_MANUAL | EV_UPDATE_REQ);
|
||||
UAVObjConnectQueue(UAVObjGetByName("GCSReceiver"), data->objEventQueue, EV_UPDATED | EV_UPDATED_MANUAL | EV_UPDATE_REQ);
|
||||
UAVObjConnectQueue(UAVObjGetByName("ObjectPersistence"), data->objEventQueue, EV_UPDATED | EV_UPDATED_MANUAL);
|
||||
|
||||
return 0;
|
||||
}
|
||||
MODULE_INITCALL(RadioComBridgeInitialize, RadioComBridgeStart)
|
||||
|
||||
/**
|
||||
* Reads UAVTalk messages froma com port and creates packets out of them.
|
||||
*/
|
||||
static void comUAVTalkTask(void *parameters)
|
||||
{
|
||||
PHPacketHandle p = NULL;
|
||||
|
||||
// Create the buffered reader.
|
||||
BufferedReadHandle f = BufferedReadInit(PIOS_COM_UAVTALK, TEMP_BUFFER_SIZE);
|
||||
|
||||
while (1) {
|
||||
|
||||
#ifdef PIOS_INCLUDE_WDG
|
||||
// Update the watchdog timer.
|
||||
PIOS_WDG_UpdateFlag(PIOS_WDG_COMUAVTALK);
|
||||
#endif /* PIOS_INCLUDE_WDG */
|
||||
|
||||
// Receive from USB HID if available, otherwise UAVTalk com if it's available.
|
||||
#if defined(PIOS_INCLUDE_USB)
|
||||
// Determine input port (USB takes priority over telemetry port)
|
||||
if (PIOS_USB_CheckAvailable(0))
|
||||
BufferedReadSetCom(f, PIOS_COM_USB_HID);
|
||||
else
|
||||
#endif /* PIOS_INCLUDE_USB */
|
||||
{
|
||||
if (PIOS_COM_UAVTALK)
|
||||
BufferedReadSetCom(f, PIOS_COM_UAVTALK);
|
||||
else
|
||||
{
|
||||
vTaskDelay(5);
|
||||
continue;
|
||||
}
|
||||
}
|
||||
|
||||
// Read the next byte
|
||||
uint8_t rx_byte;
|
||||
if(!BufferedRead(f, &rx_byte, MAX_PORT_DELAY))
|
||||
continue;
|
||||
data->txBytes++;
|
||||
|
||||
// Get a TX packet from the packet handler if required.
|
||||
if (p == NULL)
|
||||
{
|
||||
|
||||
// Wait until we receive a sync.
|
||||
UAVTalkRxState state = UAVTalkProcessInputStreamQuiet(data->inUAVTalkCon, 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)
|
||||
{
|
||||
DEBUG_PRINTF(2, "Packet dropped!\n\r");
|
||||
continue;
|
||||
}
|
||||
|
||||
// Initialize the packet.
|
||||
p->header.destination_id = data->destination_id;
|
||||
p->header.source_id = PIOS_RFM22B_DeviceID(pios_rfm22b_id);
|
||||
//p->header.type = PACKET_TYPE_ACKED_DATA;
|
||||
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(data->inUAVTalkCon, rx_byte);
|
||||
UAVTalkConnectionData *connection = (UAVTalkConnectionData*)(data->inUAVTalkCon);
|
||||
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.
|
||||
UAVObjEvent ev;
|
||||
ev.obj = iproc->obj;
|
||||
ev.instId = iproc->instId;
|
||||
ev.event = EV_SEND_ACK;
|
||||
xQueueSend(data->objEventQueue, &ev, MAX_PORT_DELAY);
|
||||
|
||||
// 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;
|
||||
}
|
||||
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.
|
||||
xQueueSend(data->sendPacketQueue, &p, MAX_PORT_DELAY);
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
UAVObjEvent ev;
|
||||
ev.obj = iproc->obj;
|
||||
ev.instId = 0;
|
||||
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.
|
||||
ev.event = EV_UPDATE_REQ;
|
||||
xQueueSend(data->objEventQueue, &ev, MAX_PORT_DELAY);
|
||||
break;
|
||||
case UAVTALK_TYPE_OBJ_ACK:
|
||||
if (UAVObjUnpack(iproc->obj, iproc->instId, connection->rxBuffer) == 0)
|
||||
{
|
||||
// Queue up an ACK
|
||||
ev.event = EV_SEND_ACK;
|
||||
xQueueSend(data->objEventQueue, &ev, MAX_PORT_DELAY);
|
||||
}
|
||||
break;
|
||||
}
|
||||
|
||||
// Release the packet, since we don't need it.
|
||||
PHReleaseTXPacket(pios_packet_handler, p);
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
// Queue the packet for transmission.
|
||||
xQueueSend(data->sendPacketQueue, &p, MAX_PORT_DELAY);
|
||||
}
|
||||
p = NULL;
|
||||
|
||||
} else if(state == UAVTALK_STATE_ERROR) {
|
||||
DEBUG_PRINTF(1, "UAVTalk FAILED!\n\r");
|
||||
data->UAVTalkErrors++;
|
||||
|
||||
// Send a NACK if required.
|
||||
if((iproc->obj) && (iproc->type == UAVTALK_TYPE_OBJ_ACK))
|
||||
{
|
||||
// Queue up a NACK
|
||||
UAVObjEvent ev;
|
||||
ev.obj = iproc->obj;
|
||||
ev.event = EV_SEND_NACK;
|
||||
xQueueSend(data->objEventQueue, &ev, MAX_PORT_DELAY);
|
||||
|
||||
// Release the packet and start over again.
|
||||
PHReleaseTXPacket(pios_packet_handler, p);
|
||||
}
|
||||
else
|
||||
{
|
||||
// Transmit the packet anyway...
|
||||
xQueueSend(data->sendPacketQueue, &p, MAX_PORT_DELAY);
|
||||
}
|
||||
p = NULL;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* The radio to com bridge task.
|
||||
*/
|
||||
static void radioReceiveTask(void *parameters)
|
||||
{
|
||||
PHPacketHandle p = NULL;
|
||||
|
||||
/* Handle radio -> usart/usb direction */
|
||||
while (1) {
|
||||
uint32_t rx_bytes;
|
||||
|
||||
#ifdef PIOS_INCLUDE_WDG
|
||||
// Update the watchdog timer.
|
||||
PIOS_WDG_UpdateFlag(PIOS_WDG_RADIORECEIVE);
|
||||
#endif /* PIOS_INCLUDE_WDG */
|
||||
|
||||
// Get a RX packet from the packet handler if required.
|
||||
if (p == NULL)
|
||||
p = PHGetRXPacket(pios_packet_handler);
|
||||
|
||||
if(p == NULL) {
|
||||
DEBUG_PRINTF(2, "RX Packet Unavailable.!\n\r");
|
||||
// Wait a bit for a packet to come available.
|
||||
vTaskDelay(5);
|
||||
continue;
|
||||
}
|
||||
|
||||
// Receive data from the radio port
|
||||
rx_bytes = PIOS_COM_ReceiveBuffer(PIOS_COM_RADIO, (uint8_t*)p, PIOS_PH_MAX_PACKET, MAX_PORT_DELAY);
|
||||
if(rx_bytes == 0)
|
||||
continue;
|
||||
data->rxBytes += rx_bytes;
|
||||
|
||||
// Verify that the packet is valid and pass it on.
|
||||
if(PHVerifyPacket(pios_packet_handler, p, rx_bytes) > 0) {
|
||||
UAVObjEvent ev;
|
||||
ev.obj = (UAVObjHandle)p;
|
||||
ev.event = EV_PACKET_RECEIVED;
|
||||
xQueueSend(data->objEventQueue, &ev, portMAX_DELAY);
|
||||
} else
|
||||
{
|
||||
data->packetErrors++;
|
||||
PHReceivePacket(pios_packet_handler, p, false);
|
||||
}
|
||||
p = NULL;
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Send packets to the radio.
|
||||
*/
|
||||
static void sendPacketTask(void *parameters)
|
||||
{
|
||||
PHPacketHandle p;
|
||||
|
||||
// Loop forever
|
||||
while (1) {
|
||||
#ifdef PIOS_INCLUDE_WDG
|
||||
// Update the watchdog timer.
|
||||
PIOS_WDG_UpdateFlag(PIOS_WDG_SENDPACKET);
|
||||
#endif /* PIOS_INCLUDE_WDG */
|
||||
// Wait for a packet on the queue.
|
||||
if (xQueueReceive(data->sendPacketQueue, &p, MAX_PORT_DELAY) == pdTRUE) {
|
||||
// Send the packet.
|
||||
if(!PHTransmitPacket(pios_packet_handler, p))
|
||||
PHReleaseTXPacket(pios_packet_handler, p);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Send packets to the radio.
|
||||
*/
|
||||
static void sendDataTask(void *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(data->objEventQueue, &ev, MAX_PORT_DELAY) == pdTRUE) {
|
||||
if ((ev.event == EV_UPDATED) || (ev.event == EV_UPDATE_REQ))
|
||||
{
|
||||
// Send update (with retries)
|
||||
uint32_t retries = 0;
|
||||
int32_t success = -1;
|
||||
while (retries < MAX_RETRIES && success == -1) {
|
||||
success = UAVTalkSendObject(data->outUAVTalkCon, ev.obj, 0, 0, RETRY_TIMEOUT_MS);
|
||||
++retries;
|
||||
}
|
||||
data->comTxRetries += retries;
|
||||
}
|
||||
else if(ev.event == EV_SEND_ACK)
|
||||
{
|
||||
// Send the ACK
|
||||
uint32_t retries = 0;
|
||||
int32_t success = -1;
|
||||
while (retries < MAX_RETRIES && success == -1) {
|
||||
success = UAVTalkSendAck(data->outUAVTalkCon, ev.obj, ev.instId);
|
||||
++retries;
|
||||
}
|
||||
data->comTxRetries += retries;
|
||||
}
|
||||
else if(ev.event == EV_SEND_NACK)
|
||||
{
|
||||
// Send the NACK
|
||||
uint32_t retries = 0;
|
||||
int32_t success = -1;
|
||||
while (retries < MAX_RETRIES && success == -1) {
|
||||
success = UAVTalkSendNack(data->outUAVTalkCon, UAVObjGetID(ev.obj));
|
||||
++retries;
|
||||
}
|
||||
data->comTxRetries += retries;
|
||||
}
|
||||
else if(ev.event == EV_PACKET_RECEIVED)
|
||||
{
|
||||
// Receive the packet.
|
||||
PHReceivePacket(pios_packet_handler, (PHPacketHandle)ev.obj, false);
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* The com to radio bridge task.
|
||||
*/
|
||||
static void transparentCommTask(void * parameters)
|
||||
{
|
||||
portTickType packet_start_time = 0;
|
||||
uint32_t timeout = MAX_PORT_DELAY;
|
||||
PHPacketHandle p = NULL;
|
||||
|
||||
/* Handle usart/usb -> radio direction */
|
||||
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)
|
||||
{
|
||||
// Wait a bit for a packet to come available.
|
||||
vTaskDelay(5);
|
||||
continue;
|
||||
}
|
||||
|
||||
// Initialize the packet.
|
||||
p->header.destination_id = data->destination_id;
|
||||
p->header.source_id = PIOS_RFM22B_DeviceID(pios_rfm22b_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.
|
||||
xQueueSend(data->sendPacketQueue, &p, MAX_PORT_DELAY);
|
||||
|
||||
// Reset the timeout
|
||||
timeout = MAX_PORT_DELAY;
|
||||
p = NULL;
|
||||
packet_start_time = 0;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* The stats update task.
|
||||
*/
|
||||
static void radioStatusTask(void *parameters)
|
||||
{
|
||||
PHStatusPacket status_packet;
|
||||
|
||||
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.RSSI = PIOS_RFM22B_RSSI(pios_rfm22b_id);
|
||||
pipxStatus.Retries = data->comTxRetries;
|
||||
pipxStatus.Errors = data->packetErrors;
|
||||
pipxStatus.UAVTalkErrors = data->UAVTalkErrors;
|
||||
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;
|
||||
|
||||
// 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++;
|
||||
// Add the paired devices stats to ours.
|
||||
if(data->pairStats[i].pairID == pairID)
|
||||
{
|
||||
pipxStatus.Retries += data->pairStats[i].retries;
|
||||
pipxStatus.Errors += data->pairStats[i].errors;
|
||||
pipxStatus.UAVTalkErrors += data->pairStats[i].uavtalk_errors;
|
||||
pipxStatus.Resets += data->pairStats[i].resets;
|
||||
pipxStatus.LinkState = PIPXSTATUS_LINKSTATE_CONNECTED;
|
||||
}
|
||||
}
|
||||
|
||||
// Update the object
|
||||
PipXStatusSet(&pipxStatus);
|
||||
|
||||
// Broadcast the status.
|
||||
{
|
||||
static uint16_t cntr = 0;
|
||||
if(cntr++ == RADIOSTATS_UPDATE_PERIOD_MS / STATS_UPDATE_PERIOD_MS)
|
||||
{
|
||||
// Queue the status message
|
||||
status_packet.header.destination_id = 0xffffffff;
|
||||
status_packet.header.type = PACKET_TYPE_STATUS;
|
||||
status_packet.header.data_size = PH_STATUS_DATA_SIZE(&status_packet);
|
||||
status_packet.header.source_id = pipxStatus.DeviceID;
|
||||
status_packet.header.rssi = pipxStatus.RSSI;
|
||||
status_packet.retries = data->comTxRetries;
|
||||
status_packet.errors = data->packetErrors;
|
||||
status_packet.uavtalk_errors = data->UAVTalkErrors;
|
||||
status_packet.resets = PIOS_RFM22B_Resets(pios_rfm22b_id);
|
||||
PHPacketHandle sph = (PHPacketHandle)&status_packet;
|
||||
xQueueSend(data->sendPacketQueue, &sph, MAX_PORT_DELAY);
|
||||
cntr = 0;
|
||||
}
|
||||
}
|
||||
|
||||
// Delay until the next update period.
|
||||
vTaskDelay(STATS_UPDATE_PERIOD_MS / portTICK_RATE_MS);
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* The PPM input task.
|
||||
*/
|
||||
static void ppmInputTask(void *parameters)
|
||||
{
|
||||
PHPpmPacket ppm_packet;
|
||||
PHPacketHandle pph = (PHPacketHandle)&ppm_packet;
|
||||
|
||||
while (1) {
|
||||
|
||||
#ifdef PIOS_INCLUDE_WDG
|
||||
// Update the watchdog timer.
|
||||
PIOS_WDG_UpdateFlag(PIOS_WDG_PPMINPUT);
|
||||
#endif /* PIOS_INCLUDE_WDG */
|
||||
|
||||
// Send the PPM packet
|
||||
for (uint8_t i = 1; i <= PIOS_PPM_NUM_INPUTS; ++i)
|
||||
ppm_packet.channels[i - 1] = PIOS_RCVR_Read(PIOS_PPM_RECEIVER, i);
|
||||
|
||||
// Send the packet.
|
||||
ppm_packet.header.destination_id = data->destination_id;
|
||||
ppm_packet.header.source_id = PIOS_RFM22B_DeviceID(pios_rfm22b_id);
|
||||
ppm_packet.header.type = PACKET_TYPE_PPM;
|
||||
ppm_packet.header.data_size = PH_PPM_DATA_SIZE(&ppm_packet);
|
||||
xQueueSend(data->sendPacketQueue, &pph, MAX_PORT_DELAY);
|
||||
|
||||
// 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] 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 transmitData(uint8_t *buf, int32_t length)
|
||||
{
|
||||
uint32_t outputPort = PIOS_COM_UAVTALK;
|
||||
#if defined(PIOS_INCLUDE_USB)
|
||||
// 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 PIOS_COM_SendBuffer(outputPort, buf, length);
|
||||
else
|
||||
return -1;
|
||||
}
|
||||
|
||||
/**
|
||||
* 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)
|
||||
{
|
||||
return PIOS_COM_SendBuffer(PIOS_COM_RADIO, (uint8_t*)p, PH_PACKET_SIZE(p));
|
||||
}
|
||||
|
||||
/**
|
||||
* 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)
|
||||
{
|
||||
// Packet data should go to transparent com if it's configured,
|
||||
// USB HID if it's connected, otherwise, UAVTalk com if it's configured.
|
||||
uint32_t outputPort = PIOS_COM_TRANS_COM;
|
||||
if (!outputPort)
|
||||
{
|
||||
outputPort = PIOS_COM_UAVTALK;
|
||||
#if defined(PIOS_INCLUDE_USB)
|
||||
// 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 status packet
|
||||
* \param[in] status The status structure
|
||||
*/
|
||||
static void StatusHandler(PHStatusPacketHandle status)
|
||||
{
|
||||
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 = status->header.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].lastContact = 0;
|
||||
}
|
||||
|
||||
// Remove any contacts that we haven't seen for a while.
|
||||
for (id_idx = 0; id_idx < PIPXSTATUS_PAIRIDS_NUMELEM; ++id_idx)
|
||||
{
|
||||
if(data->pairStats[id_idx].lastContact > MAX_LOST_CONTACT_TIME)
|
||||
{
|
||||
data->pairStats[id_idx].pairID = 0;
|
||||
data->pairStats[id_idx].rssi = -127;
|
||||
data->pairStats[id_idx].retries = 0;
|
||||
data->pairStats[id_idx].errors = 0;
|
||||
data->pairStats[id_idx].uavtalk_errors = 0;
|
||||
data->pairStats[id_idx].resets = 0;
|
||||
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 = status->header.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].lastContact = 0;
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* 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);
|
||||
}
|
||||
|
||||
static BufferedReadHandle BufferedReadInit(uint32_t com_port, uint16_t buffer_length)
|
||||
{
|
||||
BufferedReadHandle h = (BufferedReadHandle)pvPortMalloc(sizeof(ReadBuffer));
|
||||
if (!h)
|
||||
return NULL;
|
||||
|
||||
h->com_port = com_port;
|
||||
h->buffer = (uint8_t*)pvPortMalloc(buffer_length);
|
||||
h->length = buffer_length;
|
||||
h->index = 0;
|
||||
h->data_length = 0;
|
||||
|
||||
if (h->buffer == NULL)
|
||||
return NULL;
|
||||
|
||||
return h;
|
||||
}
|
||||
|
||||
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;
|
||||
}
|
||||
|
||||
// Return the next byte.
|
||||
*value = h->buffer[h->index++];
|
||||
return true;
|
||||
}
|
||||
|
||||
static void BufferedReadSetCom(BufferedReadHandle h, uint32_t com_port)
|
||||
{
|
||||
h->com_port = com_port;
|
||||
}
|
||||
|
||||
/**
|
||||
* 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.
|
||||
*/
|
||||
static void updateSettings()
|
||||
{
|
||||
|
||||
// Get the settings.
|
||||
PipXSettingsData pipxSettings;
|
||||
PipXSettingsGet(&pipxSettings);
|
||||
|
||||
// Initialize the destination ID
|
||||
data->destination_id = pipxSettings.PairID ? pipxSettings.PairID : 0xffffffff;
|
||||
DEBUG_PRINTF(2, "PairID: %x\n\r", data->destination_id);
|
||||
|
||||
if (PIOS_COM_TELEMETRY) {
|
||||
switch (pipxSettings.TelemetrySpeed) {
|
||||
case PIPXSETTINGS_TELEMETRYSPEED_2400:
|
||||
PIOS_COM_ChangeBaud(PIOS_COM_TELEMETRY, 2400);
|
||||
break;
|
||||
case PIPXSETTINGS_TELEMETRYSPEED_4800:
|
||||
PIOS_COM_ChangeBaud(PIOS_COM_TELEMETRY, 4800);
|
||||
break;
|
||||
case PIPXSETTINGS_TELEMETRYSPEED_9600:
|
||||
PIOS_COM_ChangeBaud(PIOS_COM_TELEMETRY, 9600);
|
||||
break;
|
||||
case PIPXSETTINGS_TELEMETRYSPEED_19200:
|
||||
PIOS_COM_ChangeBaud(PIOS_COM_TELEMETRY, 19200);
|
||||
break;
|
||||
case PIPXSETTINGS_TELEMETRYSPEED_38400:
|
||||
PIOS_COM_ChangeBaud(PIOS_COM_TELEMETRY, 38400);
|
||||
break;
|
||||
case PIPXSETTINGS_TELEMETRYSPEED_57600:
|
||||
PIOS_COM_ChangeBaud(PIOS_COM_TELEMETRY, 57600);
|
||||
break;
|
||||
case PIPXSETTINGS_TELEMETRYSPEED_115200:
|
||||
PIOS_COM_ChangeBaud(PIOS_COM_TELEMETRY, 115200);
|
||||
break;
|
||||
}
|
||||
}
|
||||
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;
|
||||
}
|
||||
}
|
||||
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;
|
||||
}
|
||||
}
|
||||
}
|
@ -1,41 +1,39 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file gpio_in.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @brief GPIO 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 __GPIO_IN_H__
|
||||
#define __GPIO_IN_H__
|
||||
|
||||
// *****************************************************************
|
||||
|
||||
void GPIO_IN_Init(void);
|
||||
bool GPIO_IN(uint8_t num);
|
||||
|
||||
// *****************************************************************
|
||||
|
||||
#endif
|
||||
|
||||
/**
|
||||
* @}
|
||||
* @}
|
||||
*/
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup OpenPilotModules OpenPilot Modules
|
||||
* @{
|
||||
* @addtogroup RadioComBridgeModule Com Port to Radio Bridge Module
|
||||
* @brief Bridge Com and Radio ports
|
||||
* @{
|
||||
*
|
||||
* @file radiocombridge.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @brief Include file of the telemetry module.
|
||||
* @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 RADIOCOMBRIDGE_H
|
||||
#define RADIOCOMBRIDGE_H
|
||||
|
||||
#endif // RADIOCOMBRIDGE_H
|
||||
|
||||
/**
|
||||
* @}
|
||||
* @}
|
||||
*/
|
@ -215,6 +215,7 @@ extern uint32_t pios_com_telem_usb_id;
|
||||
//------------------------
|
||||
#define PIOS_RCVR_MAX_DEVS 3
|
||||
#define PIOS_RCVR_MAX_CHANNELS 12
|
||||
#define PIOS_GCSRCVR_TIMEOUT_MS 100
|
||||
|
||||
//-------------------------
|
||||
// Receiver PPM input
|
||||
|
468
flight/PiOS/Boards/STM32103CB_PIPXTREME_Rev1.h
Normal file → Executable file
468
flight/PiOS/Boards/STM32103CB_PIPXTREME_Rev1.h
Normal file → Executable file
@ -23,20 +23,22 @@
|
||||
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
*/
|
||||
|
||||
#ifndef PIOS_BOARD_H
|
||||
#define PIOS_BOARD_H
|
||||
#ifndef STM32103CB_PIPXTREME_H_
|
||||
#define STM32103CB_PIPXTREME_H_
|
||||
|
||||
// *****************************************************************
|
||||
#define ADD_ONE_ADC
|
||||
|
||||
//------------------------
|
||||
// Timers and Channels Used
|
||||
|
||||
//------------------------
|
||||
/*
|
||||
Timer | Channel 1 | Channel 2 | Channel 3 | Channel 4
|
||||
------+------------+------------+------------+------------
|
||||
TIM1 | DELAY |
|
||||
TIM2 | | PPM Output | PPM Input |
|
||||
TIM3 | TIMER INTERRUPT |
|
||||
TIM4 | STOPWATCH |
|
||||
------+------------+------------+------------+------------
|
||||
Timer | Channel 1 | Channel 2 | Channel 3 | Channel 4
|
||||
------+-----------+-----------+-----------+----------
|
||||
TIM1 | Servo 4 | | |
|
||||
TIM2 | RC In 5 | RC In 6 | Servo 6 |
|
||||
TIM3 | Servo 5 | RC In 2 | RC In 3 | RC In 4
|
||||
TIM4 | RC In 1 | Servo 3 | Servo 2 | Servo 1
|
||||
------+-----------+-----------+-----------+----------
|
||||
*/
|
||||
|
||||
//------------------------
|
||||
@ -55,6 +57,7 @@ TIM4 | STOPWATCH |
|
||||
/* Channel 11 - */
|
||||
/* Channel 12 - */
|
||||
|
||||
|
||||
//------------------------
|
||||
// BOOTLOADER_SETTINGS
|
||||
//------------------------
|
||||
@ -63,23 +66,26 @@ TIM4 | STOPWATCH |
|
||||
#define MAX_DEL_RETRYS 3
|
||||
|
||||
|
||||
// *****************************************************************
|
||||
// System Settings
|
||||
//------------------------
|
||||
// WATCHDOG_SETTINGS
|
||||
//------------------------
|
||||
#define PIOS_WATCHDOG_TIMEOUT 500
|
||||
#define PIOS_WDG_REGISTER BKP_DR4
|
||||
#define PIOS_WDG_COMUAVTALK 0x0001
|
||||
#define PIOS_WDG_RADIORECEIVE 0x0002
|
||||
#define PIOS_WDG_SENDPACKET 0x0004
|
||||
#define PIOS_WDG_SENDDATA 0x0008
|
||||
#define PIOS_WDG_TRANSCOMM 0x0010
|
||||
#define PIOS_WDG_PPMINPUT 0x0020
|
||||
|
||||
#define PIOS_MASTER_CLOCK 72000000ul
|
||||
#define PIOS_PERIPHERAL_CLOCK (PIOS_MASTER_CLOCK / 2)
|
||||
//------------------------
|
||||
// TELEMETRY
|
||||
//------------------------
|
||||
#define TELEM_QUEUE_SIZE 20
|
||||
|
||||
// *****************************************************************
|
||||
// Interrupt Priorities
|
||||
|
||||
#define PIOS_IRQ_PRIO_LOW 12 // lower than RTOS
|
||||
#define PIOS_IRQ_PRIO_MID 8 // higher than RTOS
|
||||
#define PIOS_IRQ_PRIO_HIGH 5 // for SPI, ADC, I2C etc...
|
||||
#define PIOS_IRQ_PRIO_HIGHEST 4 // for USART etc...
|
||||
|
||||
// *****************************************************************
|
||||
//------------------------
|
||||
// PIOS_LED
|
||||
|
||||
//------------------------
|
||||
#define PIOS_LED_USB 0
|
||||
#define PIOS_LED_LINK 1
|
||||
#define PIOS_LED_RX 2
|
||||
@ -104,17 +110,27 @@ TIM4 | STOPWATCH |
|
||||
#define TX_LED_OFF PIOS_LED_Off(PIOS_LED_TX)
|
||||
#define TX_LED_TOGGLE PIOS_LED_Toggle(PIOS_LED_TX)
|
||||
|
||||
// *****************************************************************
|
||||
// Timer interrupt
|
||||
//-------------------------
|
||||
// System Settings
|
||||
//-------------------------
|
||||
#define PIOS_MASTER_CLOCK 72000000
|
||||
#define PIOS_PERIPHERAL_CLOCK (PIOS_MASTER_CLOCK / 2)
|
||||
|
||||
#define TIMER_INT_TIMER TIM3
|
||||
#define TIMER_INT_FUNC TIM3_IRQHandler
|
||||
#define TIMER_INT_PRIORITY 2
|
||||
//-------------------------
|
||||
// Interrupt Priorities
|
||||
//-------------------------
|
||||
#define PIOS_IRQ_PRIO_LOW 12 // lower than RTOS
|
||||
#define PIOS_IRQ_PRIO_MID 8 // higher than RTOS
|
||||
#define PIOS_IRQ_PRIO_HIGH 5 // for SPI, ADC, I2C etc...
|
||||
#define PIOS_IRQ_PRIO_HIGHEST 4 // for USART etc...
|
||||
|
||||
// *****************************************************************
|
||||
// Stop watch timer
|
||||
|
||||
#define STOPWATCH_TIMER TIM4
|
||||
//------------------------
|
||||
// PIOS_I2C
|
||||
// See also pios_board.c
|
||||
//------------------------
|
||||
#define PIOS_I2C_MAX_DEVS 1
|
||||
extern uint32_t pios_i2c_flexi_adapter_id;
|
||||
#define PIOS_I2C_MAIN_ADAPTER (pios_i2c_flexi_adapter_id)
|
||||
|
||||
//------------------------
|
||||
// PIOS_SPI
|
||||
@ -126,286 +142,170 @@ extern uint32_t pios_spi_port_id;
|
||||
|
||||
//-------------------------
|
||||
// PIOS_USART
|
||||
//
|
||||
// See also pios_board.c
|
||||
//-------------------------
|
||||
#define PIOS_USART_MAX_DEVS 1
|
||||
#define PIOS_USART_MAX_DEVS 3
|
||||
|
||||
//-------------------------
|
||||
// PIOS_COM
|
||||
//
|
||||
// See also pios_board.c
|
||||
//-------------------------
|
||||
#define PIOS_COM_MAX_DEVS 2
|
||||
#define PIOS_COM_MAX_DEVS 5
|
||||
|
||||
extern uint32_t pios_com_serial_id;
|
||||
#define PIOS_COM_SERIAL (pios_com_serial_id)
|
||||
//#define PIOS_COM_DEBUG PIOS_COM_SERIAL // uncomment this to send debug info out the serial port
|
||||
|
||||
#if defined(PIOS_INCLUDE_USB_HID)
|
||||
extern uint32_t pios_com_telem_usb_id;
|
||||
#define PIOS_COM_TELEM_USB (pios_com_telem_usb_id)
|
||||
#endif
|
||||
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_trans_com_id;
|
||||
extern uint32_t pios_com_debug_id;
|
||||
extern uint32_t pios_com_rfm22b_id;
|
||||
extern uint32_t pios_ppm_rcvr_id;
|
||||
#define PIOS_COM_USB_HID (pios_com_telem_usb_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_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_PPM_RECEIVER (pios_ppm_rcvr_id)
|
||||
|
||||
#if defined(PIOS_COM_DEBUG)
|
||||
// #define DEBUG_PRINTF(...) PIOS_COM_SendFormattedString(PIOS_COM_DEBUG, __VA_ARGS__)
|
||||
#define DEBUG_PRINTF(...) PIOS_COM_SendFormattedStringNonBlocking(PIOS_COM_DEBUG, __VA_ARGS__)
|
||||
#define DEBUG_LEVEL 2
|
||||
#if DEBUG_LEVEL > 0
|
||||
#define DEBUG_PRINTF(level, ...) {if(level <= DEBUG_LEVEL && PIOS_COM_DEBUG > 0) { PIOS_COM_SendFormattedStringNonBlocking(PIOS_COM_DEBUG, __VA_ARGS__); }}
|
||||
#else
|
||||
#define DEBUG_PRINTF(...)
|
||||
#define DEBUG_PRINTF(...)
|
||||
#endif
|
||||
#define RFM22_DEBUG 1
|
||||
|
||||
//-------------------------
|
||||
// PPM input/output
|
||||
//-------------------------
|
||||
#define PIOS_PPM_IN_GPIO_PORT GPIOB
|
||||
#define PIOS_PPM_IN_GPIO_PIN GPIO_Pin_11
|
||||
#define PIOS_PPM_IN_TIM_CHANNEL TIM_Channel_4
|
||||
#define PIOS_PPM_IN_TIM_CCR TIM_IT_CC4
|
||||
#define PIOS_PPM_IN_TIM_GETCAP_FUNC TIM_GetCapture4
|
||||
|
||||
#define PIOS_PPM_OUT_GPIO_PORT GPIOB
|
||||
#define PIOS_PPM_OUT_GPIO_PIN GPIO_Pin_10
|
||||
#define PIOS_PPM_OUT_TIM_CHANNEL TIM_Channel_3
|
||||
#define PIOS_PPM_OUT_TIM_CCR TIM_IT_CC3
|
||||
|
||||
#define PIOS_PPM_MAX_CHANNELS 7
|
||||
#define PIOS_PPM_TIM_PORT TIM2
|
||||
#define PIOS_PPM_TIM TIM2
|
||||
#define PIOS_PPM_TIM_IRQ TIM2_IRQn
|
||||
#define PIOS_PPM_CC_IRQ_FUNC TIM2_IRQHandler
|
||||
#define PIOS_PPM_TIMER_EN_RCC_FUNC RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM2, ENABLE)
|
||||
#define PIOS_PPM_TIMER_DIS_RCC_FUNC RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM2, DISABLE)
|
||||
|
||||
// *****************************************************************
|
||||
// ADC
|
||||
// None
|
||||
//-------------------------
|
||||
//#define PIOS_ADC_OVERSAMPLING_RATE 1
|
||||
#define PIOS_ADC_USE_TEMP_SENSOR 0
|
||||
#define PIOS_ADC_TEMP_SENSOR_ADC ADC1
|
||||
#define PIOS_ADC_TEMP_SENSOR_ADC_CHANNEL 1
|
||||
|
||||
// PIOS_ADC_PinGet(0) = Temperature Sensor (On-board)
|
||||
// PIOS_ADC_PinGet(1) = PSU Voltage
|
||||
#define PIOS_ADC_NUM_PINS 0
|
||||
|
||||
#define PIOS_ADC_OVERSAMPLING_RATE 2
|
||||
#define PIOS_ADC_PORTS { }
|
||||
#define PIOS_ADC_PINS { }
|
||||
#define PIOS_ADC_CHANNELS { }
|
||||
#define PIOS_ADC_MAPPING { }
|
||||
#define PIOS_ADC_CHANNEL_MAPPING { }
|
||||
#define PIOS_ADC_NUM_CHANNELS (PIOS_ADC_NUM_PINS + PIOS_ADC_USE_TEMP_SENSOR)
|
||||
#define PIOS_ADC_NUM_ADC_CHANNELS 0
|
||||
#define PIOS_ADC_USE_ADC2 0
|
||||
#define PIOS_ADC_CLOCK_FUNCTION RCC_APB2PeriphClockCmd(RCC_APB2Periph_ADC1 | RCC_APB2Periph_ADC2, ENABLE)
|
||||
#define PIOS_ADC_ADCCLK RCC_PCLK2_Div8
|
||||
/* RCC_PCLK2_Div2: ADC clock = PCLK2/2 */
|
||||
/* RCC_PCLK2_Div4: ADC clock = PCLK2/4 */
|
||||
/* RCC_PCLK2_Div6: ADC clock = PCLK2/6 */
|
||||
/* RCC_PCLK2_Div8: ADC clock = PCLK2/8 */
|
||||
#define PIOS_ADC_SAMPLE_TIME ADC_SampleTime_239Cycles5
|
||||
/* Sample time: */
|
||||
/* With an ADCCLK = 14 MHz and a sampling time of 239.5 cycles: */
|
||||
/* Tconv = 239.5 + 12.5 = 252 cycles = 18<31>s */
|
||||
/* (1 / (ADCCLK / CYCLES)) = Sample Time (<28>S) */
|
||||
#define PIOS_ADC_IRQ_PRIO PIOS_IRQ_PRIO_LOW
|
||||
|
||||
#define PIOS_ADC_USE_TEMP_SENSOR 1
|
||||
#define PIOS_ADC_TEMP_SENSOR_ADC ADC1
|
||||
#define PIOS_ADC_TEMP_SENSOR_ADC_CHANNEL 16 // Temperature sensor channel
|
||||
//#define PIOS_ADC_TEMP_SENSOR_ADC_CHANNEL 17 // VREF channel
|
||||
// Currently analog acquistion hard coded at 480 Hz
|
||||
// PCKL2 = HCLK / 16
|
||||
// ADCCLK = PCLK2 / 2
|
||||
#define PIOS_ADC_RATE (72.0e6 / 1.0 / 8.0 / 252.0 / (PIOS_ADC_NUM_CHANNELS >> PIOS_ADC_USE_ADC2))
|
||||
#define PIOS_ADC_MAX_OVERSAMPLING 36
|
||||
|
||||
#define PIOS_ADC_PIN1_GPIO_PORT GPIOB // Port B (PSU Voltage)
|
||||
#define PIOS_ADC_PIN1_GPIO_PIN GPIO_Pin_1 // PB1 .. ADC12_IN9
|
||||
#define PIOS_ADC_PIN1_GPIO_CHANNEL ADC_Channel_9
|
||||
#define PIOS_ADC_PIN1_ADC ADC2
|
||||
#define PIOS_ADC_PIN1_ADC_NUMBER 1
|
||||
//------------------------
|
||||
// PIOS_RCVR
|
||||
// See also pios_board.c
|
||||
//------------------------
|
||||
#define PIOS_RCVR_MAX_DEVS 3
|
||||
#define PIOS_RCVR_MAX_CHANNELS 12
|
||||
#define PIOS_GCSRCVR_TIMEOUT_MS 100
|
||||
|
||||
#define PIOS_ADC_NUM_PINS 1
|
||||
//-------------------------
|
||||
// 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_ADC_PORTS { PIOS_ADC_PIN1_GPIO_PORT }
|
||||
#define PIOS_ADC_PINS { PIOS_ADC_PIN1_GPIO_PIN }
|
||||
#define PIOS_ADC_CHANNELS { PIOS_ADC_PIN1_GPIO_CHANNEL }
|
||||
#define PIOS_ADC_MAPPING { PIOS_ADC_PIN1_ADC }
|
||||
#define PIOS_ADC_CHANNEL_MAPPING { PIOS_ADC_PIN1_ADC_NUMBER }
|
||||
//-------------------------
|
||||
// Servo outputs
|
||||
//-------------------------
|
||||
#define PIOS_SERVO_UPDATE_HZ 50
|
||||
#define PIOS_SERVOS_INITIAL_POSITION 0 /* dont want to start motors, have no pulse till settings loaded */
|
||||
|
||||
#define PIOS_ADC_NUM_CHANNELS (PIOS_ADC_NUM_PINS + PIOS_ADC_USE_TEMP_SENSOR)
|
||||
#define PIOS_ADC_NUM_ADC_CHANNELS 2
|
||||
#define PIOS_ADC_USE_ADC2 1
|
||||
#define PIOS_ADC_CLOCK_FUNCTION RCC_APB2PeriphClockCmd(RCC_APB2Periph_ADC1 | RCC_APB2Periph_ADC2, ENABLE)
|
||||
//#define PIOS_ADC_ADCCLK RCC_PCLK2_Div2 // ADC clock = PCLK2/2
|
||||
//#define PIOS_ADC_ADCCLK RCC_PCLK2_Div4 // ADC clock = PCLK2/4
|
||||
//#define PIOS_ADC_ADCCLK RCC_PCLK2_Div6 // ADC clock = PCLK2/6
|
||||
#define PIOS_ADC_ADCCLK RCC_PCLK2_Div8 // ADC clock = PCLK2/8
|
||||
//#define PIOS_ADC_SAMPLE_TIME ADC_SampleTime_1Cycles5
|
||||
//#define PIOS_ADC_SAMPLE_TIME ADC_SampleTime_7Cycles5
|
||||
//#define PIOS_ADC_SAMPLE_TIME ADC_SampleTime_13Cycles5
|
||||
//#define PIOS_ADC_SAMPLE_TIME ADC_SampleTime_28Cycles5
|
||||
//#define PIOS_ADC_SAMPLE_TIME ADC_SampleTime_41Cycles5
|
||||
//#define PIOS_ADC_SAMPLE_TIME ADC_SampleTime_55Cycles5
|
||||
//#define PIOS_ADC_SAMPLE_TIME ADC_SampleTime_71Cycles5
|
||||
#define PIOS_ADC_SAMPLE_TIME ADC_SampleTime_239Cycles5
|
||||
/* Sample time: */
|
||||
/* With an ADCCLK = 14 MHz and a sampling time of 293.5 cycles: */
|
||||
/* Tconv = 239.5 + 12.5 = 252 cycles = 18<31>s */
|
||||
/* (1 / (ADCCLK / CYCLES)) = Sample Time (<28>S) */
|
||||
#define PIOS_ADC_IRQ_PRIO 3
|
||||
#define PIOS_ADC_MAX_OVERSAMPLING 1
|
||||
#define PIOS_ADC_RATE (72.0e6 / 1 / 8 / 252 / (PIOS_ADC_NUM_ADC_CHANNELS >> PIOS_ADC_USE_ADC2))
|
||||
//--------------------------
|
||||
// Timer controller settings
|
||||
//--------------------------
|
||||
#define PIOS_TIM_MAX_DEVS 3
|
||||
|
||||
// *****************************************************************
|
||||
// GPIO output pins
|
||||
//-------------------------
|
||||
// GPIO
|
||||
//-------------------------
|
||||
#define PIOS_GPIO_PORTS { }
|
||||
#define PIOS_GPIO_PINS { }
|
||||
#define PIOS_GPIO_CLKS { }
|
||||
#define PIOS_GPIO_NUM 0
|
||||
|
||||
// GPIO_Mode_Out_OD Open Drain Output
|
||||
// GPIO_Mode_Out_PP Push-Pull Output
|
||||
// GPIO_Mode_AF_OD Open Drain Output Alternate-Function
|
||||
// GPIO_Mode_AF_PP Push-Pull Output Alternate-Function
|
||||
|
||||
// Serial port RTS line
|
||||
#define PIOS_GPIO_OUT_0_PORT GPIOB
|
||||
#define PIOS_GPIO_OUT_0_PIN GPIO_Pin_15
|
||||
#define PIOS_GPIO_OUT_0_GPIO_CLK RCC_APB2Periph_GPIOB
|
||||
|
||||
// RF module chip-select line
|
||||
#define PIOS_GPIO_OUT_1_PORT GPIOA
|
||||
#define PIOS_GPIO_OUT_1_PIN GPIO_Pin_4
|
||||
#define PIOS_GPIO_OUT_1_GPIO_CLK RCC_APB2Periph_GPIOA
|
||||
|
||||
// PPM OUT line
|
||||
#define PIOS_GPIO_OUT_2_PORT GPIOB
|
||||
#define PIOS_GPIO_OUT_2_PIN GPIO_Pin_10
|
||||
#define PIOS_GPIO_OUT_2_GPIO_CLK RCC_APB2Periph_GPIOB
|
||||
|
||||
// spare pin
|
||||
#define PIOS_GPIO_OUT_3_PORT GPIOA
|
||||
#define PIOS_GPIO_OUT_3_PIN GPIO_Pin_0
|
||||
#define PIOS_GPIO_OUT_3_GPIO_CLK RCC_APB2Periph_GPIOA
|
||||
|
||||
// spare pin
|
||||
#define PIOS_GPIO_OUT_4_PORT GPIOA
|
||||
#define PIOS_GPIO_OUT_4_PIN GPIO_Pin_1
|
||||
#define PIOS_GPIO_OUT_4_GPIO_CLK RCC_APB2Periph_GPIOA
|
||||
|
||||
// spare pin
|
||||
#define PIOS_GPIO_OUT_5_PORT GPIOC
|
||||
#define PIOS_GPIO_OUT_5_PIN GPIO_Pin_13
|
||||
#define PIOS_GPIO_OUT_5_GPIO_CLK RCC_APB2Periph_GPIOC
|
||||
|
||||
// spare pin
|
||||
#define PIOS_GPIO_OUT_6_PORT GPIOC
|
||||
#define PIOS_GPIO_OUT_6_PIN GPIO_Pin_14
|
||||
#define PIOS_GPIO_OUT_6_GPIO_CLK RCC_APB2Periph_GPIOC
|
||||
|
||||
// spare pin
|
||||
#define PIOS_GPIO_OUT_7_PORT GPIOC
|
||||
#define PIOS_GPIO_OUT_7_PIN GPIO_Pin_15
|
||||
#define PIOS_GPIO_OUT_7_GPIO_CLK RCC_APB2Periph_GPIOC
|
||||
|
||||
#define PIOS_GPIO_NUM 8
|
||||
#define PIOS_GPIO_PORTS {PIOS_GPIO_OUT_0_PORT, PIOS_GPIO_OUT_1_PORT, PIOS_GPIO_OUT_2_PORT, PIOS_GPIO_OUT_3_PORT, PIOS_GPIO_OUT_4_PORT, PIOS_GPIO_OUT_5_PORT, PIOS_GPIO_OUT_6_PORT, PIOS_GPIO_OUT_7_PORT}
|
||||
#define PIOS_GPIO_PINS {PIOS_GPIO_OUT_0_PIN, PIOS_GPIO_OUT_1_PIN, PIOS_GPIO_OUT_2_PIN, PIOS_GPIO_OUT_3_PIN, PIOS_GPIO_OUT_4_PIN, PIOS_GPIO_OUT_5_PIN, PIOS_GPIO_OUT_6_PIN, PIOS_GPIO_OUT_7_PIN}
|
||||
#define PIOS_GPIO_CLKS {PIOS_GPIO_OUT_0_GPIO_CLK, PIOS_GPIO_OUT_1_GPIO_CLK, PIOS_GPIO_OUT_2_GPIO_CLK, PIOS_GPIO_OUT_3_GPIO_CLK, PIOS_GPIO_OUT_4_GPIO_CLK, PIOS_GPIO_OUT_5_GPIO_CLK, PIOS_GPIO_OUT_6_GPIO_CLK, PIOS_GPIO_OUT_7_GPIO_CLK}
|
||||
|
||||
#define SERIAL_RTS_ENABLE PIOS_GPIO_Enable(0)
|
||||
#define SERIAL_RTS_SET PIOS_GPIO_Off(0)
|
||||
#define SERIAL_RTS_CLEAR PIOS_GPIO_On(0)
|
||||
|
||||
#define RF_CS_ENABLE PIOS_GPIO_Enable(1)
|
||||
#define RF_CS_HIGH PIOS_GPIO_Off(1)
|
||||
#define RF_CS_LOW PIOS_GPIO_On(1)
|
||||
|
||||
#define PPM_OUT_PIN PIOS_GPIO_OUT_2_PIN
|
||||
#define PPM_OUT_PORT PIOS_GPIO_OUT_2_PORT
|
||||
#define PPM_OUT_ENABLE PIOS_GPIO_Enable(2)
|
||||
#define PPM_OUT_HIGH PIOS_GPIO_Off(2)
|
||||
#define PPM_OUT_LOW PIOS_GPIO_On(2)
|
||||
|
||||
#define SPARE1_ENABLE PIOS_GPIO_Enable(3)
|
||||
#define SPARE1_HIGH PIOS_GPIO_Off(3)
|
||||
#define SPARE1_LOW PIOS_GPIO_On(3)
|
||||
|
||||
#define SPARE2_ENABLE PIOS_GPIO_Enable(4)
|
||||
#define SPARE2_HIGH PIOS_GPIO_Off(4)
|
||||
#define SPARE2_LOW PIOS_GPIO_On(4)
|
||||
|
||||
#define SPARE3_ENABLE PIOS_GPIO_Enable(5)
|
||||
#define SPARE3_HIGH PIOS_GPIO_Off(5)
|
||||
#define SPARE3_LOW PIOS_GPIO_On(5)
|
||||
|
||||
#define SPARE4_ENABLE PIOS_GPIO_Enable(6)
|
||||
#define SPARE4_HIGH PIOS_GPIO_Off(6)
|
||||
#define SPARE4_LOW PIOS_GPIO_On(6)
|
||||
|
||||
#define SPARE5_ENABLE PIOS_GPIO_Enable(7)
|
||||
#define SPARE5_HIGH PIOS_GPIO_Off(7)
|
||||
#define SPARE5_LOW PIOS_GPIO_On(7)
|
||||
|
||||
// *****************************************************************
|
||||
// GPIO input pins
|
||||
|
||||
// GPIO_Mode_AIN Analog Input
|
||||
// GPIO_Mode_IN_FLOATING Input Floating
|
||||
// GPIO_Mode_IPD Input Pull-Down
|
||||
// GPIO_Mode_IPU Input Pull-up
|
||||
|
||||
// API mode line
|
||||
#define GPIO_IN_0_PORT GPIOB
|
||||
#define GPIO_IN_0_PIN GPIO_Pin_13
|
||||
#define GPIO_IN_0_MODE GPIO_Mode_IPU
|
||||
|
||||
// Serial port CTS line
|
||||
#define GPIO_IN_1_PORT GPIOB
|
||||
#define GPIO_IN_1_PIN GPIO_Pin_14
|
||||
#define GPIO_IN_1_MODE GPIO_Mode_IPU
|
||||
|
||||
// VBUS sense line
|
||||
#define GPIO_IN_2_PORT GPIOA
|
||||
#define GPIO_IN_2_PIN GPIO_Pin_8
|
||||
#define GPIO_IN_2_MODE GPIO_Mode_IN_FLOATING
|
||||
|
||||
// 868MHz jumper option
|
||||
#define GPIO_IN_3_PORT GPIOB
|
||||
#define GPIO_IN_3_PIN GPIO_Pin_8
|
||||
#define GPIO_IN_3_MODE GPIO_Mode_IPU
|
||||
|
||||
// 915MHz jumper option
|
||||
#define GPIO_IN_4_PORT GPIOB
|
||||
#define GPIO_IN_4_PIN GPIO_Pin_9
|
||||
#define GPIO_IN_4_MODE GPIO_Mode_IPU
|
||||
|
||||
// RF INT line
|
||||
#define GPIO_IN_5_PORT GPIOA
|
||||
#define GPIO_IN_5_PIN GPIO_Pin_2
|
||||
#define GPIO_IN_5_MODE GPIO_Mode_IN_FLOATING
|
||||
|
||||
// RF misc line
|
||||
#define GPIO_IN_6_PORT GPIOB
|
||||
#define GPIO_IN_6_PIN GPIO_Pin_0
|
||||
#define GPIO_IN_6_MODE GPIO_Mode_IN_FLOATING
|
||||
|
||||
// PPM IN line
|
||||
#define PPM_IN_PORT GPIOB
|
||||
#define PPM_IN_PIN GPIO_Pin_11
|
||||
#define PPM_IN_MODE GPIO_Mode_IPD
|
||||
|
||||
#define GPIO_IN_NUM 8
|
||||
#define GPIO_IN_PORTS { GPIO_IN_0_PORT, GPIO_IN_1_PORT, GPIO_IN_2_PORT, GPIO_IN_3_PORT, GPIO_IN_4_PORT, GPIO_IN_5_PORT, GPIO_IN_6_PORT, PPM_IN_PORT }
|
||||
#define GPIO_IN_PINS { GPIO_IN_0_PIN, GPIO_IN_1_PIN, GPIO_IN_2_PIN, GPIO_IN_3_PIN, GPIO_IN_4_PIN, GPIO_IN_5_PIN, GPIO_IN_6_PIN, PPM_IN_PIN }
|
||||
#define GPIO_IN_MODES { GPIO_IN_0_MODE, GPIO_IN_1_MODE, GPIO_IN_2_MODE, GPIO_IN_3_MODE, GPIO_IN_4_MODE, GPIO_IN_5_MODE, GPIO_IN_6_MODE, PPM_IN_MODE }
|
||||
|
||||
#define API_MODE_PIN 0
|
||||
#define SERIAL_CTS_PIN 1
|
||||
#define VBUS_SENSE_PIN 2
|
||||
#define _868MHz_PIN 3
|
||||
#define _915MHz_PIN 4
|
||||
#define RF_INT_PIN 5
|
||||
#define RF_MISC_PIN 6
|
||||
|
||||
// *****************************************************************
|
||||
//-------------------------
|
||||
// USB
|
||||
//-------------------------
|
||||
#define PIOS_USB_HID_MAX_DEVS 1
|
||||
#define PIOS_USB_ENABLED 1
|
||||
#define PIOS_USB_HID_MAX_DEVS 1
|
||||
#define PIOS_USB_MAX_DEVS 1
|
||||
#define PIOS_USB_DETECT_GPIO_PORT GPIOC
|
||||
#define PIOS_USB_DETECT_GPIO_PIN GPIO_Pin_15
|
||||
#define PIOS_USB_DETECT_EXTI_LINE EXTI_Line15
|
||||
|
||||
#if defined(PIOS_INCLUDE_USB_HID)
|
||||
#define PIOS_USB_ENABLED 1
|
||||
#define PIOS_USB_MAX_DEVS 1
|
||||
#define PIOS_USB_DETECT_GPIO_PORT GPIO_IN_2_PORT
|
||||
#define PIOS_USB_DETECT_GPIO_PIN GPIO_IN_2_PIN
|
||||
#define PIOS_USB_DETECT_EXTI_LINE EXTI_Line4
|
||||
#define PIOS_IRQ_USB_PRIORITY 8
|
||||
#endif
|
||||
#define PIOS_USB_HID_MAX_DEVS 1
|
||||
|
||||
// *****************************************************************
|
||||
//-------------------------
|
||||
// RFM22
|
||||
//-------------------------
|
||||
|
||||
//#define RFM22_EXT_INT_USE
|
||||
|
||||
#define RFM22_PIOS_SPI PIOS_SPI_PORT // SPIx
|
||||
extern uint32_t pios_rfm22b_id;
|
||||
#define RFM22_EXT_INT_USE
|
||||
#define RFM22_PIOS_SPI PIOS_SPI_PORT // SPIx
|
||||
|
||||
#if defined(RFM22_EXT_INT_USE)
|
||||
#define RFM22_EXT_INT_PORT_SOURCE GPIO_PortSourceGPIOA
|
||||
#define RFM22_EXT_INT_PIN_SOURCE GPIO_PinSource2
|
||||
|
||||
#define RFM22_EXT_INT_LINE EXTI_Line2
|
||||
#define RFM22_EXT_INT_IRQn EXTI2_IRQn
|
||||
#define RFM22_EXT_INT_FUNC EXTI2_IRQHandler
|
||||
|
||||
#define RFM22_EXT_INT_PRIORITY 1
|
||||
#define PIOS_RFM22_EXTI_GPIO_PORT GPIOA
|
||||
#define PIOS_RFM22_EXTI_GPIO_PIN GPIO_Pin_2
|
||||
#define PIOS_RFM22_EXTI_PORT_SOURCE GPIO_PortSourceGPIOA
|
||||
#define PIOS_RFM22_EXTI_PIN_SOURCE GPIO_PinSource2
|
||||
#define PIOS_RFM22_EXTI_CLK RCC_APB2Periph_GPIOA
|
||||
#define PIOS_RFM22_EXTI_LINE EXTI_Line2
|
||||
#define PIOS_RFM22_EXTI_IRQn EXTI2_IRQn
|
||||
#define PIOS_RFM22_EXTI_PRIO PIOS_IRQ_PRIO_LOW
|
||||
#endif
|
||||
|
||||
// *****************************************************************
|
||||
//-------------------------
|
||||
// Packet Handler
|
||||
//-------------------------
|
||||
|
||||
#endif /* PIOS_BOARD_H */
|
||||
uint32_t pios_packet_handler;
|
||||
#define PIOS_INCLUDE_PACKET_HANDLER
|
||||
#define PIOS_PH_MAX_PACKET 255
|
||||
#define PIOS_PH_WIN_SIZE 3
|
||||
#define PIOS_PH_MAX_CONNECTIONS 1
|
||||
|
||||
//-------------------------
|
||||
// Reed-Solomon ECC
|
||||
//-------------------------
|
||||
|
||||
#define RS_ECC_NPARITY 4
|
||||
|
||||
//-------------------------
|
||||
// Flash EEPROM Emulation
|
||||
//-------------------------
|
||||
|
||||
#define PIOS_FLASH_SIZE 0x20000
|
||||
#define PIOS_FLASH_EEPROM_START_ADDR 0x08000000
|
||||
#define PIOS_FLASH_PAGE_SIZE 1024
|
||||
#define PIOS_FLASH_EEPROM_ADDR (PIOS_FLASH_EEPROM_START_ADDR + PIOS_FLASH_SIZE - PIOS_FLASH_PAGE_SIZE)
|
||||
#define PIOS_FLASH_EEPROM_LEN PIOS_FLASH_PAGE_SIZE
|
||||
|
||||
#endif /* STM32103CB_PIPXTREME_H_ */
|
||||
|
@ -29,6 +29,76 @@ static const uint8_t crc_table[256] = {
|
||||
0xde, 0xd9, 0xd0, 0xd7, 0xc2, 0xc5, 0xcc, 0xcb, 0xe6, 0xe1, 0xe8, 0xef, 0xfa, 0xfd, 0xf4, 0xf3
|
||||
};
|
||||
|
||||
static const uint16_t CRC_Table16[] = { // HDLC polynomial
|
||||
0x0000, 0x1189, 0x2312, 0x329b, 0x4624, 0x57ad, 0x6536, 0x74bf,
|
||||
0x8c48, 0x9dc1, 0xaf5a, 0xbed3, 0xca6c, 0xdbe5, 0xe97e, 0xf8f7,
|
||||
0x1081, 0x0108, 0x3393, 0x221a, 0x56a5, 0x472c, 0x75b7, 0x643e,
|
||||
0x9cc9, 0x8d40, 0xbfdb, 0xae52, 0xdaed, 0xcb64, 0xf9ff, 0xe876,
|
||||
0x2102, 0x308b, 0x0210, 0x1399, 0x6726, 0x76af, 0x4434, 0x55bd,
|
||||
0xad4a, 0xbcc3, 0x8e58, 0x9fd1, 0xeb6e, 0xfae7, 0xc87c, 0xd9f5,
|
||||
0x3183, 0x200a, 0x1291, 0x0318, 0x77a7, 0x662e, 0x54b5, 0x453c,
|
||||
0xbdcb, 0xac42, 0x9ed9, 0x8f50, 0xfbef, 0xea66, 0xd8fd, 0xc974,
|
||||
0x4204, 0x538d, 0x6116, 0x709f, 0x0420, 0x15a9, 0x2732, 0x36bb,
|
||||
0xce4c, 0xdfc5, 0xed5e, 0xfcd7, 0x8868, 0x99e1, 0xab7a, 0xbaf3,
|
||||
0x5285, 0x430c, 0x7197, 0x601e, 0x14a1, 0x0528, 0x37b3, 0x263a,
|
||||
0xdecd, 0xcf44, 0xfddf, 0xec56, 0x98e9, 0x8960, 0xbbfb, 0xaa72,
|
||||
0x6306, 0x728f, 0x4014, 0x519d, 0x2522, 0x34ab, 0x0630, 0x17b9,
|
||||
0xef4e, 0xfec7, 0xcc5c, 0xddd5, 0xa96a, 0xb8e3, 0x8a78, 0x9bf1,
|
||||
0x7387, 0x620e, 0x5095, 0x411c, 0x35a3, 0x242a, 0x16b1, 0x0738,
|
||||
0xffcf, 0xee46, 0xdcdd, 0xcd54, 0xb9eb, 0xa862, 0x9af9, 0x8b70,
|
||||
0x8408, 0x9581, 0xa71a, 0xb693, 0xc22c, 0xd3a5, 0xe13e, 0xf0b7,
|
||||
0x0840, 0x19c9, 0x2b52, 0x3adb, 0x4e64, 0x5fed, 0x6d76, 0x7cff,
|
||||
0x9489, 0x8500, 0xb79b, 0xa612, 0xd2ad, 0xc324, 0xf1bf, 0xe036,
|
||||
0x18c1, 0x0948, 0x3bd3, 0x2a5a, 0x5ee5, 0x4f6c, 0x7df7, 0x6c7e,
|
||||
0xa50a, 0xb483, 0x8618, 0x9791, 0xe32e, 0xf2a7, 0xc03c, 0xd1b5,
|
||||
0x2942, 0x38cb, 0x0a50, 0x1bd9, 0x6f66, 0x7eef, 0x4c74, 0x5dfd,
|
||||
0xb58b, 0xa402, 0x9699, 0x8710, 0xf3af, 0xe226, 0xd0bd, 0xc134,
|
||||
0x39c3, 0x284a, 0x1ad1, 0x0b58, 0x7fe7, 0x6e6e, 0x5cf5, 0x4d7c,
|
||||
0xc60c, 0xd785, 0xe51e, 0xf497, 0x8028, 0x91a1, 0xa33a, 0xb2b3,
|
||||
0x4a44, 0x5bcd, 0x6956, 0x78df, 0x0c60, 0x1de9, 0x2f72, 0x3efb,
|
||||
0xd68d, 0xc704, 0xf59f, 0xe416, 0x90a9, 0x8120, 0xb3bb, 0xa232,
|
||||
0x5ac5, 0x4b4c, 0x79d7, 0x685e, 0x1ce1, 0x0d68, 0x3ff3, 0x2e7a,
|
||||
0xe70e, 0xf687, 0xc41c, 0xd595, 0xa12a, 0xb0a3, 0x8238, 0x93b1,
|
||||
0x6b46, 0x7acf, 0x4854, 0x59dd, 0x2d62, 0x3ceb, 0x0e70, 0x1ff9,
|
||||
0xf78f, 0xe606, 0xd49d, 0xc514, 0xb1ab, 0xa022, 0x92b9, 0x8330,
|
||||
0x7bc7, 0x6a4e, 0x58d5, 0x495c, 0x3de3, 0x2c6a, 0x1ef1, 0x0f78
|
||||
};
|
||||
|
||||
static const uint32_t CRC_Table32[] = {
|
||||
0x00000000, 0x04c11db7, 0x09823b6e, 0x0d4326d9, 0x130476dc, 0x17c56b6b, 0x1a864db2, 0x1e475005,
|
||||
0x2608edb8, 0x22c9f00f, 0x2f8ad6d6, 0x2b4bcb61, 0x350c9b64, 0x31cd86d3, 0x3c8ea00a, 0x384fbdbd,
|
||||
0x4c11db70, 0x48d0c6c7, 0x4593e01e, 0x4152fda9, 0x5f15adac, 0x5bd4b01b, 0x569796c2, 0x52568b75,
|
||||
0x6a1936c8, 0x6ed82b7f, 0x639b0da6, 0x675a1011, 0x791d4014, 0x7ddc5da3, 0x709f7b7a, 0x745e66cd,
|
||||
0x9823b6e0, 0x9ce2ab57, 0x91a18d8e, 0x95609039, 0x8b27c03c, 0x8fe6dd8b, 0x82a5fb52, 0x8664e6e5,
|
||||
0xbe2b5b58, 0xbaea46ef, 0xb7a96036, 0xb3687d81, 0xad2f2d84, 0xa9ee3033, 0xa4ad16ea, 0xa06c0b5d,
|
||||
0xd4326d90, 0xd0f37027, 0xddb056fe, 0xd9714b49, 0xc7361b4c, 0xc3f706fb, 0xceb42022, 0xca753d95,
|
||||
0xf23a8028, 0xf6fb9d9f, 0xfbb8bb46, 0xff79a6f1, 0xe13ef6f4, 0xe5ffeb43, 0xe8bccd9a, 0xec7dd02d,
|
||||
0x34867077, 0x30476dc0, 0x3d044b19, 0x39c556ae, 0x278206ab, 0x23431b1c, 0x2e003dc5, 0x2ac12072,
|
||||
0x128e9dcf, 0x164f8078, 0x1b0ca6a1, 0x1fcdbb16, 0x018aeb13, 0x054bf6a4, 0x0808d07d, 0x0cc9cdca,
|
||||
0x7897ab07, 0x7c56b6b0, 0x71159069, 0x75d48dde, 0x6b93dddb, 0x6f52c06c, 0x6211e6b5, 0x66d0fb02,
|
||||
0x5e9f46bf, 0x5a5e5b08, 0x571d7dd1, 0x53dc6066, 0x4d9b3063, 0x495a2dd4, 0x44190b0d, 0x40d816ba,
|
||||
0xaca5c697, 0xa864db20, 0xa527fdf9, 0xa1e6e04e, 0xbfa1b04b, 0xbb60adfc, 0xb6238b25, 0xb2e29692,
|
||||
0x8aad2b2f, 0x8e6c3698, 0x832f1041, 0x87ee0df6, 0x99a95df3, 0x9d684044, 0x902b669d, 0x94ea7b2a,
|
||||
0xe0b41de7, 0xe4750050, 0xe9362689, 0xedf73b3e, 0xf3b06b3b, 0xf771768c, 0xfa325055, 0xfef34de2,
|
||||
0xc6bcf05f, 0xc27dede8, 0xcf3ecb31, 0xcbffd686, 0xd5b88683, 0xd1799b34, 0xdc3abded, 0xd8fba05a,
|
||||
0x690ce0ee, 0x6dcdfd59, 0x608edb80, 0x644fc637, 0x7a089632, 0x7ec98b85, 0x738aad5c, 0x774bb0eb,
|
||||
0x4f040d56, 0x4bc510e1, 0x46863638, 0x42472b8f, 0x5c007b8a, 0x58c1663d, 0x558240e4, 0x51435d53,
|
||||
0x251d3b9e, 0x21dc2629, 0x2c9f00f0, 0x285e1d47, 0x36194d42, 0x32d850f5, 0x3f9b762c, 0x3b5a6b9b,
|
||||
0x0315d626, 0x07d4cb91, 0x0a97ed48, 0x0e56f0ff, 0x1011a0fa, 0x14d0bd4d, 0x19939b94, 0x1d528623,
|
||||
0xf12f560e, 0xf5ee4bb9, 0xf8ad6d60, 0xfc6c70d7, 0xe22b20d2, 0xe6ea3d65, 0xeba91bbc, 0xef68060b,
|
||||
0xd727bbb6, 0xd3e6a601, 0xdea580d8, 0xda649d6f, 0xc423cd6a, 0xc0e2d0dd, 0xcda1f604, 0xc960ebb3,
|
||||
0xbd3e8d7e, 0xb9ff90c9, 0xb4bcb610, 0xb07daba7, 0xae3afba2, 0xaafbe615, 0xa7b8c0cc, 0xa379dd7b,
|
||||
0x9b3660c6, 0x9ff77d71, 0x92b45ba8, 0x9675461f, 0x8832161a, 0x8cf30bad, 0x81b02d74, 0x857130c3,
|
||||
0x5d8a9099, 0x594b8d2e, 0x5408abf7, 0x50c9b640, 0x4e8ee645, 0x4a4ffbf2, 0x470cdd2b, 0x43cdc09c,
|
||||
0x7b827d21, 0x7f436096, 0x7200464f, 0x76c15bf8, 0x68860bfd, 0x6c47164a, 0x61043093, 0x65c52d24,
|
||||
0x119b4be9, 0x155a565e, 0x18197087, 0x1cd86d30, 0x029f3d35, 0x065e2082, 0x0b1d065b, 0x0fdc1bec,
|
||||
0x3793a651, 0x3352bbe6, 0x3e119d3f, 0x3ad08088, 0x2497d08d, 0x2056cd3a, 0x2d15ebe3, 0x29d4f654,
|
||||
0xc5a92679, 0xc1683bce, 0xcc2b1d17, 0xc8ea00a0, 0xd6ad50a5, 0xd26c4d12, 0xdf2f6bcb, 0xdbee767c,
|
||||
0xe3a1cbc1, 0xe760d676, 0xea23f0af, 0xeee2ed18, 0xf0a5bd1d, 0xf464a0aa, 0xf9278673, 0xfde69bc4,
|
||||
0x89b8fd09, 0x8d79e0be, 0x803ac667, 0x84fbdbd0, 0x9abc8bd5, 0x9e7d9662, 0x933eb0bb, 0x97ffad0c,
|
||||
0xafb010b1, 0xab710d06, 0xa6322bdf, 0xa2f33668, 0xbcb4666d, 0xb8757bda, 0xb5365d03, 0xb1f740b4
|
||||
};
|
||||
|
||||
/**
|
||||
* Update the crc value with new data.
|
||||
*
|
||||
@ -52,7 +122,7 @@ uint8_t PIOS_CRC_updateByte(uint8_t crc, const uint8_t data)
|
||||
return crc_table[crc ^ data];
|
||||
}
|
||||
|
||||
/*
|
||||
/**
|
||||
* @brief Update a CRC with a data buffer
|
||||
* @param[in] crc Starting CRC value
|
||||
* @param[in] data Data buffer
|
||||
@ -72,3 +142,58 @@ uint8_t PIOS_CRC_updateCRC(uint8_t crc, const uint8_t* data, int32_t length)
|
||||
return crc8;
|
||||
}
|
||||
|
||||
/**
|
||||
* Update the crc value with new data.
|
||||
* \param crc The current crc value.
|
||||
* \param data Pointer to a buffer of \a data_len bytes.
|
||||
* \param length Number of bytes in the \a data buffer.
|
||||
* \return The updated crc value.
|
||||
*/
|
||||
uint16_t PIOS_CRC16_updateByte(uint16_t crc, const uint8_t data)
|
||||
{
|
||||
return ((crc >> 8) ^ CRC_Table16[(crc & 0xff) ^ data]);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Update a CRC with a data buffer
|
||||
* @param[in] crc Starting CRC value
|
||||
* @param[in] data Data buffer
|
||||
* @param[in] length Number of bytes to process
|
||||
* @returns Updated CRC
|
||||
*/
|
||||
uint16_t PIOS_CRC16_updateCRC(uint16_t crc, const uint8_t* data, int32_t length)
|
||||
{
|
||||
register uint8_t *p = (uint8_t *)data;
|
||||
register uint16_t _crc = crc;
|
||||
for (register uint32_t i = length; i > 0; i--)
|
||||
_crc = (_crc >> 8) ^ CRC_Table16[(_crc ^ *p++) & 0xff];
|
||||
return _crc;
|
||||
}
|
||||
|
||||
/**
|
||||
* Update the crc value with new data.
|
||||
* \param crc The current crc value.
|
||||
* \param data Pointer to a buffer of \a data_len bytes.
|
||||
* \param length Number of bytes in the \a data buffer.
|
||||
* \return The updated crc value.
|
||||
*/
|
||||
uint32_t PIOS_CRC32_updateByte(uint32_t crc, const uint8_t data)
|
||||
{
|
||||
return ((crc << 8) ^ CRC_Table32[(crc >> 24) ^ data]);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Update a CRC with a data buffer
|
||||
* @param[in] crc Starting CRC value
|
||||
* @param[in] data Data buffer
|
||||
* @param[in] length Number of bytes to process
|
||||
* @returns Updated CRC
|
||||
*/
|
||||
uint32_t PIOS_CRC32_updateCRC(uint32_t crc, const uint8_t* data, int32_t length)
|
||||
{
|
||||
register uint8_t *p = (uint8_t *)data;
|
||||
register uint32_t _crc = crc;
|
||||
for (register uint32_t i = length; i > 0; i--)
|
||||
_crc = (_crc << 8) ^ CRC_Table32[(_crc >> 24) ^ *p++];
|
||||
return _crc;
|
||||
}
|
||||
|
@ -152,10 +152,9 @@ static void PIOS_gcsrcvr_Supervisor(uint32_t gcsrcvr_id) {
|
||||
}
|
||||
|
||||
/*
|
||||
* RTC runs at 625Hz so divide down the base rate so
|
||||
* that this loop runs at 25Hz.
|
||||
* RTC runs at 625Hz.
|
||||
*/
|
||||
if(++(gcsrcvr_dev->supv_timer) < 25) {
|
||||
if(++(gcsrcvr_dev->supv_timer) < (PIOS_GCSRCVR_TIMEOUT_MS * 1000 / 625)) {
|
||||
return;
|
||||
}
|
||||
gcsrcvr_dev->supv_timer = 0;
|
||||
|
2407
flight/PiOS/Common/pios_rfm22b.c
Normal file
2407
flight/PiOS/Common/pios_rfm22b.c
Normal file
@ -0,0 +1,2407 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup PIOS PIOS Core hardware abstraction layer
|
||||
* @{
|
||||
* @addtogroup PIOS_RFM22B Radio Functions
|
||||
* @brief PIOS interface for for the RFM22B radio
|
||||
* @{
|
||||
*
|
||||
* @file pios_rfm22b.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
|
||||
*/
|
||||
|
||||
// *****************************************************************
|
||||
// RFM22B hardware layer
|
||||
//
|
||||
// This module uses the RFM22B's internal packet handling hardware to
|
||||
// encapsulate our own packet data.
|
||||
//
|
||||
// The RFM22B internal hardware packet handler configuration is as follows ..
|
||||
//
|
||||
// 4-byte (32-bit) preamble .. alternating 0's & 1's
|
||||
// 4-byte (32-bit) sync
|
||||
// 1-byte packet length (number of data bytes to follow)
|
||||
// 0 to 255 user data bytes
|
||||
//
|
||||
// Our own packet data will also contain it's own header and 32-bit CRC
|
||||
// as a single 16-bit CRC is not sufficient for wireless comms.
|
||||
//
|
||||
// *****************************************************************
|
||||
|
||||
/* Project Includes */
|
||||
#include "pios.h"
|
||||
|
||||
#if defined(PIOS_INCLUDE_RFM22B)
|
||||
|
||||
#include <string.h> // memmove
|
||||
|
||||
#include <stm32f10x.h>
|
||||
#include <stopwatch.h>
|
||||
|
||||
#include <packet_handler.h>
|
||||
|
||||
#include <pios_rfm22b_priv.h>
|
||||
|
||||
/* Local Defines */
|
||||
#define STACK_SIZE_BYTES 200
|
||||
|
||||
// RTC timer is running at 625Hz (1.6ms or 5 ticks == 8ms).
|
||||
// A 256 byte message at 56kbps should take less than 40ms
|
||||
// Note: This timeout should be rate dependent.
|
||||
#define PIOS_RFM22B_SUPERVISOR_TIMEOUT 65 // ~100ms
|
||||
|
||||
// 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
|
||||
#define OSC_LOAD_CAP_2 0x7B // board 2
|
||||
#define OSC_LOAD_CAP_3 0x7E // board 3
|
||||
#define OSC_LOAD_CAP_4 0x7F // board 4
|
||||
|
||||
// ************************************
|
||||
|
||||
#define TX_TEST_MODE_TIMELIMIT_MS 30000 // TX test modes time limit (in ms)
|
||||
|
||||
//#define TX_PREAMBLE_NIBBLES 8 // 7 to 511 (number of nibbles)
|
||||
//#define RX_PREAMBLE_NIBBLES 5 // 5 to 31 (number of nibbles)
|
||||
#define TX_PREAMBLE_NIBBLES 12 // 7 to 511 (number of nibbles)
|
||||
#define RX_PREAMBLE_NIBBLES 6 // 5 to 31 (number of nibbles)
|
||||
|
||||
// the size of the rf modules internal transmit buffers.
|
||||
#define TX_BUFFER_SIZE 256
|
||||
// the size of the rf modules internal FIFO buffers
|
||||
#define FIFO_SIZE 64
|
||||
|
||||
#define TX_FIFO_HI_WATERMARK 62 // 0-63
|
||||
#define TX_FIFO_LO_WATERMARK 32 // 0-63
|
||||
|
||||
#define RX_FIFO_HI_WATERMARK 32 // 0-63
|
||||
|
||||
#define PREAMBLE_BYTE 0x55 // preamble byte (preceeds SYNC_BYTE's)
|
||||
|
||||
#define SYNC_BYTE_1 0x2D // RF sync bytes (32-bit in all)
|
||||
#define SYNC_BYTE_2 0xD4 //
|
||||
#define SYNC_BYTE_3 0x4B //
|
||||
#define SYNC_BYTE_4 0x59 //
|
||||
|
||||
// ************************************
|
||||
// the default TX power level
|
||||
|
||||
#define RFM22_DEFAULT_RF_POWER RFM22_tx_pwr_txpow_0 // +1dBm ... 1.25mW
|
||||
//#define RFM22_DEFAULT_RF_POWER RFM22_tx_pwr_txpow_1 // +2dBm ... 1.6mW
|
||||
//#define RFM22_DEFAULT_RF_POWER RFM22_tx_pwr_txpow_2 // +5dBm ... 3.16mW
|
||||
//#define RFM22_DEFAULT_RF_POWER RFM22_tx_pwr_txpow_3 // +8dBm ... 6.3mW
|
||||
//#define RFM22_DEFAULT_RF_POWER RFM22_tx_pwr_txpow_4 // +11dBm .. 12.6mW
|
||||
//#define RFM22_DEFAULT_RF_POWER RFM22_tx_pwr_txpow_5 // +14dBm .. 25mW
|
||||
//#define RFM22_DEFAULT_RF_POWER RFM22_tx_pwr_txpow_6 // +17dBm .. 50mW
|
||||
//#define RFM22_DEFAULT_RF_POWER RFM22_tx_pwr_txpow_7 // +20dBm .. 100mW
|
||||
|
||||
// ************************************
|
||||
// the default RF datarate
|
||||
|
||||
//#define RFM22_DEFAULT_RF_DATARATE 500 // 500 bits per sec
|
||||
//#define RFM22_DEFAULT_RF_DATARATE 1000 // 1k bits per sec
|
||||
//#define RFM22_DEFAULT_RF_DATARATE 2000 // 2k bits per sec
|
||||
//#define RFM22_DEFAULT_RF_DATARATE 4000 // 4k bits per sec
|
||||
//#define RFM22_DEFAULT_RF_DATARATE 8000 // 8k bits per sec
|
||||
//#define RFM22_DEFAULT_RF_DATARATE 9600 // 9.6k bits per sec
|
||||
//#define RFM22_DEFAULT_RF_DATARATE 16000 // 16k bits per sec
|
||||
//#define RFM22_DEFAULT_RF_DATARATE 19200 // 19k2 bits per sec
|
||||
//#define RFM22_DEFAULT_RF_DATARATE 24000 // 24k bits per sec
|
||||
//#define RFM22_DEFAULT_RF_DATARATE 32000 // 32k bits per sec
|
||||
//#define RFM22_DEFAULT_RF_DATARATE 64000 // 64k bits per sec
|
||||
#define RFM22_DEFAULT_RF_DATARATE 128000 // 128k bits per sec
|
||||
//#define RFM22_DEFAULT_RF_DATARATE 192000 // 192k bits per sec
|
||||
//#define RFM22_DEFAULT_RF_DATARATE 256000 // 256k bits per sec .. NOT YET WORKING
|
||||
|
||||
// ************************************
|
||||
|
||||
#define RFM22_DEFAULT_SS_RF_DATARATE 125 // 128bps
|
||||
|
||||
// ************************************
|
||||
// Normal data streaming
|
||||
// GFSK modulation
|
||||
// no manchester encoding
|
||||
// data whitening
|
||||
// FIFO mode
|
||||
// 5-nibble rx preamble length detection
|
||||
// 10-nibble tx preamble length
|
||||
// AFC enabled
|
||||
|
||||
/* Local type definitions */
|
||||
enum pios_rfm22b_dev_magic {
|
||||
PIOS_RFM22B_DEV_MAGIC = 0x68e971b6,
|
||||
};
|
||||
|
||||
struct pios_rfm22b_dev {
|
||||
enum pios_rfm22b_dev_magic magic;
|
||||
struct pios_rfm22b_cfg cfg;
|
||||
|
||||
uint32_t deviceID;
|
||||
|
||||
// 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 supervisor countdown timer.
|
||||
uint16_t supv_timer;
|
||||
uint16_t resets;
|
||||
};
|
||||
|
||||
uint32_t random32 = 0x459ab8d8;
|
||||
|
||||
/* Local function forwared declarations */
|
||||
static void PIOS_RFM22B_Supervisor(uint32_t ppm_id);
|
||||
static void rfm22_processInt(void);
|
||||
static void PIOS_RFM22_EXT_Int(void);
|
||||
static void rfm22_setTxMode(uint8_t mode);
|
||||
|
||||
// SPI read/write functions
|
||||
void rfm22_startBurstWrite(uint8_t addr);
|
||||
inline void rfm22_burstWrite(uint8_t data)
|
||||
{
|
||||
PIOS_SPI_TransferByte(RFM22_PIOS_SPI, data);
|
||||
}
|
||||
void rfm22_endBurstWrite(void);
|
||||
void rfm22_write(uint8_t addr, uint8_t data);
|
||||
void rfm22_startBurstRead(uint8_t addr);
|
||||
inline uint8_t rfm22_burstRead(void)
|
||||
{
|
||||
return PIOS_SPI_TransferByte(RFM22_PIOS_SPI, 0xff);
|
||||
}
|
||||
void rfm22_endBurstRead(void);
|
||||
uint8_t rfm22_read(uint8_t addr);
|
||||
uint8_t rfm22_txStart();
|
||||
|
||||
/* 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,
|
||||
};
|
||||
|
||||
// External interrupt configuration
|
||||
static const struct pios_exti_cfg pios_exti_rfm22b_cfg __exti_config = {
|
||||
.vector = PIOS_RFM22_EXT_Int,
|
||||
.line = PIOS_RFM22_EXTI_LINE,
|
||||
.pin = {
|
||||
.gpio = PIOS_RFM22_EXTI_GPIO_PORT,
|
||||
.init = {
|
||||
.GPIO_Pin = PIOS_RFM22_EXTI_GPIO_PIN,
|
||||
.GPIO_Mode = GPIO_Mode_IN_FLOATING,
|
||||
},
|
||||
},
|
||||
.irq = {
|
||||
.init = {
|
||||
.NVIC_IRQChannel = PIOS_RFM22_EXTI_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_RFM22_EXTI_PRIO,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
.exti = {
|
||||
.init = {
|
||||
.EXTI_Line = PIOS_RFM22_EXTI_LINE,
|
||||
.EXTI_Mode = EXTI_Mode_Interrupt,
|
||||
.EXTI_Trigger = EXTI_Trigger_Falling,
|
||||
.EXTI_LineCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
// xtal 10 ppm, 434MHz
|
||||
#define LOOKUP_SIZE 14
|
||||
const uint32_t data_rate[] = { 500, 1000, 2000, 4000, 8000, 9600, 16000, 19200, 24000, 32000, 64000, 128000, 192000, 256000};
|
||||
const uint8_t modulation_index[] = { 16, 8, 4, 2, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1};
|
||||
const uint32_t freq_deviation[] = { 4000, 4000, 4000, 4000, 4000, 4800, 8000, 9600, 12000, 16000, 32000, 64000, 96000, 128000};
|
||||
const uint32_t rx_bandwidth[] = { 17500, 17500, 17500, 17500, 17500, 19400, 32200, 38600, 51200, 64100, 137900, 269300, 420200, 518800};
|
||||
const int8_t est_rx_sens_dBm[] = { -118, -118, -117, -116, -115, -115, -112, -112, -110, -109, -106, -103, -101, -100}; // estimated receiver sensitivity for BER = 1E-3
|
||||
|
||||
const uint8_t reg_1C[] = { 0x37, 0x37, 0x37, 0x37, 0x3A, 0x3B, 0x26, 0x28, 0x2E, 0x16, 0x07, 0x83, 0x8A, 0x8C}; // rfm22_if_filter_bandwidth
|
||||
|
||||
const uint8_t reg_1D[] = { 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44}; // rfm22_afc_loop_gearshift_override
|
||||
const uint8_t reg_1E[] = { 0x0A, 0x0A, 0x0A, 0x0A, 0x0A, 0x0A, 0x0A, 0x0A, 0x0A, 0x0A, 0x0A, 0x0A, 0x0A, 0x02}; // rfm22_afc_timing_control
|
||||
|
||||
const uint8_t reg_1F[] = { 0x03, 0x03, 0x03, 0x03, 0x03, 0x03, 0x03, 0x03, 0x03, 0x03, 0x03, 0x03, 0x03, 0x03}; // rfm22_clk_recovery_gearshift_override
|
||||
const uint8_t reg_20[] = { 0xE8, 0xF4, 0xFA, 0x70, 0x3F, 0x34, 0x3F, 0x34, 0x2A, 0x3F, 0x3F, 0x5E, 0x3F, 0x2F}; // rfm22_clk_recovery_oversampling_ratio
|
||||
const uint8_t reg_21[] = { 0x60, 0x20, 0x00, 0x01, 0x02, 0x02, 0x02, 0x02, 0x03, 0x02, 0x02, 0x01, 0x02, 0x02}; // rfm22_clk_recovery_offset2
|
||||
const uint8_t reg_22[] = { 0x20, 0x41, 0x83, 0x06, 0x0C, 0x75, 0x0C, 0x75, 0x12, 0x0C, 0x0C, 0x5D, 0x0C, 0xBB}; // rfm22_clk_recovery_offset1
|
||||
const uint8_t reg_23[] = { 0xC5, 0x89, 0x12, 0x25, 0x4A, 0x25, 0x4A, 0x25, 0x6F, 0x4A, 0x4A, 0x86, 0x4A, 0x0D}; // rfm22_clk_recovery_offset0
|
||||
const uint8_t reg_24[] = { 0x00, 0x00, 0x00, 0x02, 0x07, 0x07, 0x07, 0x07, 0x07, 0x07, 0x07, 0x05, 0x07, 0x07}; // rfm22_clk_recovery_timing_loop_gain1
|
||||
const uint8_t reg_25[] = { 0x0A, 0x23, 0x85, 0x0E, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x74, 0xFF, 0xFF}; // rfm22_clk_recovery_timing_loop_gain0
|
||||
|
||||
const uint8_t reg_2A[] = { 0x0E, 0x0E, 0x0E, 0x0E, 0x0E, 0x0D, 0x0D, 0x0E, 0x12, 0x17, 0x31, 0x50, 0x50, 0x50}; // rfm22_afc_limiter .. AFC_pull_in_range = ±AFCLimiter[7:0] x (hbsel+1) x 625 Hz
|
||||
|
||||
const uint8_t reg_6E[] = { 0x04, 0x08, 0x10, 0x20, 0x41, 0x4E, 0x83, 0x9D, 0xC4, 0x08, 0x10, 0x20, 0x31, 0x41}; // rfm22_tx_data_rate1
|
||||
const uint8_t reg_6F[] = { 0x19, 0x31, 0x62, 0xC5, 0x89, 0xA5, 0x12, 0x49, 0x9C, 0x31, 0x62, 0xC5, 0x27, 0x89}; // rfm22_tx_data_rate0
|
||||
|
||||
const uint8_t reg_70[] = { 0x2D, 0x2D, 0x2D, 0x2D, 0x2D, 0x2D, 0x2D, 0x2D, 0x2D, 0x0D, 0x0D, 0x0D, 0x0D, 0x0D}; // rfm22_modulation_mode_control1
|
||||
const uint8_t reg_71[] = { 0x23, 0x23, 0x23, 0x23, 0x23, 0x23, 0x23, 0x23, 0x23, 0x23, 0x23, 0x23, 0x23, 0x23}; // rfm22_modulation_mode_control2
|
||||
|
||||
const uint8_t reg_72[] = { 0x06, 0x06, 0x06, 0x06, 0x06, 0x08, 0x0D, 0x0F, 0x13, 0x1A, 0x33, 0x66, 0x9A, 0xCD}; // rfm22_frequency_deviation
|
||||
|
||||
// ************************************
|
||||
// Scan Spectrum settings
|
||||
// GFSK modulation
|
||||
// no manchester encoding
|
||||
// data whitening
|
||||
// FIFO mode
|
||||
// 5-nibble rx preamble length detection
|
||||
// 10-nibble tx preamble length
|
||||
#define SS_LOOKUP_SIZE 2
|
||||
|
||||
// xtal 1 ppm, 434MHz
|
||||
const uint32_t ss_rx_bandwidth[] = { 2600, 10600};
|
||||
|
||||
const uint8_t ss_reg_1C[] = { 0x51, 0x32}; // rfm22_if_filter_bandwidth
|
||||
const uint8_t ss_reg_1D[] = { 0x00, 0x00}; // rfm22_afc_loop_gearshift_override
|
||||
|
||||
const uint8_t ss_reg_20[] = { 0xE8, 0x38}; // rfm22_clk_recovery_oversampling_ratio
|
||||
const uint8_t ss_reg_21[] = { 0x60, 0x02}; // rfm22_clk_recovery_offset2
|
||||
const uint8_t ss_reg_22[] = { 0x20, 0x4D}; // rfm22_clk_recovery_offset1
|
||||
const uint8_t ss_reg_23[] = { 0xC5, 0xD3}; // rfm22_clk_recovery_offset0
|
||||
const uint8_t ss_reg_24[] = { 0x00, 0x07}; // rfm22_clk_recovery_timing_loop_gain1
|
||||
const uint8_t ss_reg_25[] = { 0x0F, 0xFF}; // rfm22_clk_recovery_timing_loop_gain0
|
||||
|
||||
const uint8_t ss_reg_2A[] = { 0xFF, 0xFF}; // rfm22_afc_limiter .. AFC_pull_in_range = ±AFCLimiter[7:0] x (hbsel+1) x 625 Hz
|
||||
|
||||
const uint8_t ss_reg_70[] = { 0x24, 0x2D}; // rfm22_modulation_mode_control1
|
||||
const uint8_t ss_reg_71[] = { 0x2B, 0x23}; // rfm22_modulation_mode_control2
|
||||
|
||||
// ************************************
|
||||
|
||||
volatile bool initialized = false;
|
||||
|
||||
struct pios_rfm22b_dev * rfm22b_dev;
|
||||
|
||||
#if defined(RFM22_EXT_INT_USE)
|
||||
volatile bool exec_using_spi; // set this if you want to access the SPI bus outside of the interrupt
|
||||
#endif
|
||||
|
||||
uint8_t device_type; // the RF chips device ID number
|
||||
uint8_t device_version; // the RF chips revision number
|
||||
|
||||
volatile uint8_t rf_mode; // holds our current RF mode
|
||||
|
||||
uint32_t lower_carrier_frequency_limit_Hz; // the minimum RF frequency we can use
|
||||
uint32_t upper_carrier_frequency_limit_Hz; // the maximum RF frequency we can use
|
||||
uint32_t carrier_frequency_hz; // the current RF frequency we are on
|
||||
|
||||
uint32_t carrier_datarate_bps; // the RF data rate we are using
|
||||
|
||||
uint32_t rf_bandwidth_used; // the RF bandwidth currently used
|
||||
uint32_t ss_rf_bandwidth_used; // the RF bandwidth currently used
|
||||
|
||||
uint8_t hbsel; // holds the hbsel (1 or 2)
|
||||
float frequency_step_size; // holds the minimum frequency step size
|
||||
|
||||
uint8_t frequency_hop_channel; // current frequency hop channel
|
||||
|
||||
uint8_t frequency_hop_step_size_reg; //
|
||||
|
||||
uint8_t adc_config; // holds the adc config reg value
|
||||
|
||||
volatile uint8_t device_status; // device status register
|
||||
volatile uint8_t int_status1; // interrupt status register 1
|
||||
volatile uint8_t int_status2; // interrupt status register 2
|
||||
volatile uint8_t ezmac_status; // ezmac status register
|
||||
|
||||
volatile int16_t afc_correction; // afc correction reading
|
||||
volatile int32_t afc_correction_Hz; // afc correction reading (in Hz)
|
||||
|
||||
volatile int16_t temperature_reg; // the temperature sensor reading
|
||||
|
||||
#if defined(RFM22_DEBUG)
|
||||
volatile uint8_t prev_device_status; // just for debugging
|
||||
volatile uint8_t prev_int_status1; // " "
|
||||
volatile uint8_t prev_int_status2; // " "
|
||||
volatile uint8_t prev_ezmac_status; // " "
|
||||
|
||||
const char *debug_msg = NULL;
|
||||
const char *error_msg = NULL;
|
||||
static uint32_t debug_val = 0;
|
||||
#endif
|
||||
|
||||
volatile uint8_t osc_load_cap; // xtal frequency calibration value
|
||||
|
||||
volatile uint8_t rssi; // the current RSSI (register value)
|
||||
volatile int8_t rssi_dBm; // dBm value
|
||||
|
||||
// the transmit power to use for data transmissions
|
||||
uint8_t tx_power;
|
||||
// the tx power register read back
|
||||
volatile uint8_t tx_pwr;
|
||||
|
||||
// The transmit buffer. Holds data that is being transmitted.
|
||||
uint8_t tx_buffer[TX_BUFFER_SIZE] __attribute__ ((aligned(4)));
|
||||
// The transmit buffer. Hosts data that is wating to be transmitted.
|
||||
uint8_t tx_pre_buffer[TX_BUFFER_SIZE] __attribute__ ((aligned(4)));
|
||||
// The tx pre-buffer write index.
|
||||
uint16_t tx_pre_buffer_size;
|
||||
// the tx data read index
|
||||
volatile uint16_t tx_data_rd;
|
||||
// the tx data write index
|
||||
volatile uint16_t tx_data_wr;
|
||||
|
||||
// the current receive buffer in use (double buffer)
|
||||
volatile uint8_t rx_buffer_current;
|
||||
// the receive buffer .. received packet data is saved here
|
||||
volatile uint8_t rx_buffer[258] __attribute__ ((aligned(4)));
|
||||
// the receive buffer write index
|
||||
volatile uint16_t rx_buffer_wr;
|
||||
|
||||
// the received packet
|
||||
volatile int8_t rx_packet_start_rssi_dBm; //
|
||||
volatile int8_t rx_packet_start_afc_Hz; //
|
||||
volatile int8_t rx_packet_rssi_dBm; // the received packet signal strength
|
||||
volatile int8_t rx_packet_afc_Hz; // the receive packet frequency offset
|
||||
|
||||
int lookup_index;
|
||||
int ss_lookup_index;
|
||||
|
||||
volatile bool power_on_reset; // set if the RF module has reset itself
|
||||
|
||||
volatile uint16_t rfm22_int_timer; // used to detect if the RF module stops responding. thus act accordingly if it does stop responding.
|
||||
volatile uint16_t rfm22_int_time_outs; // counter
|
||||
volatile uint16_t prev_rfm22_int_time_outs; //
|
||||
|
||||
uint16_t timeout_ms = 20000; //
|
||||
uint16_t timeout_sync_ms = 3; //
|
||||
uint16_t timeout_data_ms = 20; //
|
||||
|
||||
struct pios_rfm22b_dev * rfm22b_dev_g;
|
||||
|
||||
|
||||
static bool PIOS_RFM22B_validate(struct pios_rfm22b_dev * rfm22b_dev)
|
||||
{
|
||||
return (rfm22b_dev->magic == PIOS_RFM22B_DEV_MAGIC);
|
||||
}
|
||||
|
||||
#if defined(PIOS_INCLUDE_FREERTOS)
|
||||
static struct pios_rfm22b_dev * PIOS_RFM22B_alloc(void)
|
||||
{
|
||||
struct pios_rfm22b_dev * rfm22b_dev;
|
||||
|
||||
rfm22b_dev = (struct pios_rfm22b_dev *)pvPortMalloc(sizeof(*rfm22b_dev));
|
||||
if (!rfm22b_dev) return(NULL);
|
||||
rfm22b_dev_g = rfm22b_dev;
|
||||
|
||||
rfm22b_dev->magic = PIOS_RFM22B_DEV_MAGIC;
|
||||
return(rfm22b_dev);
|
||||
}
|
||||
#else
|
||||
static struct pios_rfm22b_dev pios_rfm22b_devs[PIOS_RFM22B_MAX_DEVS];
|
||||
static uint8_t pios_rfm22b_num_devs;
|
||||
static struct pios_rfm22b_dev * PIOS_RFM22B_alloc(void)
|
||||
{
|
||||
struct pios_rfm22b_dev * rfm22b_dev;
|
||||
|
||||
if (pios_rfm22b_num_devs >= PIOS_RFM22B_MAX_DEVS)
|
||||
return NULL;
|
||||
|
||||
rfm22b_dev = &pios_rfm22b_devs[pios_rfm22b_num_devs++];
|
||||
rfm22b_dev->magic = PIOS_RFM22B_DEV_MAGIC;
|
||||
|
||||
return (rfm22b_dev);
|
||||
}
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Initialise an RFM22B device
|
||||
*/
|
||||
int32_t PIOS_RFM22B_Init(uint32_t *rfm22b_id, const struct pios_rfm22b_cfg *cfg)
|
||||
{
|
||||
PIOS_DEBUG_Assert(rfm22b_id);
|
||||
PIOS_DEBUG_Assert(cfg);
|
||||
|
||||
// Allocate the device structure.
|
||||
rfm22b_dev = (struct pios_rfm22b_dev *) PIOS_RFM22B_alloc();
|
||||
if (!rfm22b_dev)
|
||||
return(-1);
|
||||
|
||||
// Bind the configuration to the device instance
|
||||
rfm22b_dev->cfg = *cfg;
|
||||
|
||||
*rfm22b_id = (uint32_t)rfm22b_dev;
|
||||
|
||||
// Initialize the TX pre-buffer pointer.
|
||||
tx_pre_buffer_size = 0;
|
||||
|
||||
// Create our (hopefully) unique 32 bit id from the processor serial number.
|
||||
uint8_t crcs[] = { 0, 0, 0, 0 };
|
||||
{
|
||||
char serial_no_str[33];
|
||||
PIOS_SYS_SerialNumberGet(serial_no_str);
|
||||
// Create a 32 bit value using 4 8 bit CRC values.
|
||||
for (uint8_t i = 0; serial_no_str[i] != 0; ++i)
|
||||
crcs[i % 4] = PIOS_CRC_updateByte(crcs[i % 4], serial_no_str[i]);
|
||||
}
|
||||
rfm22b_dev->deviceID = crcs[0] | crcs[1] << 8 | crcs[2] << 16 | crcs[3] << 24;
|
||||
DEBUG_PRINTF(2, "RF device ID: %x\n\r", rfm22b_dev->deviceID);
|
||||
|
||||
// Initialize the supervisor timer.
|
||||
rfm22b_dev->supv_timer = PIOS_RFM22B_SUPERVISOR_TIMEOUT;
|
||||
rfm22b_dev->resets = 0;
|
||||
|
||||
// Initialize the radio device.
|
||||
int initval = rfm22_init_normal(rfm22b_dev->deviceID, cfg->minFrequencyHz, cfg->maxFrequencyHz, 50000);
|
||||
|
||||
if (initval < 0)
|
||||
{
|
||||
|
||||
// RF module error .. flash the LED's
|
||||
#if defined(PIOS_COM_DEBUG)
|
||||
DEBUG_PRINTF(2, "RF ERROR res: %d\n\r\n\r", initval);
|
||||
#endif
|
||||
|
||||
for(unsigned int j = 0; j < 16; j++)
|
||||
{
|
||||
USB_LED_ON;
|
||||
LINK_LED_ON;
|
||||
RX_LED_OFF;
|
||||
TX_LED_OFF;
|
||||
|
||||
PIOS_DELAY_WaitmS(200);
|
||||
|
||||
USB_LED_OFF;
|
||||
LINK_LED_OFF;
|
||||
RX_LED_ON;
|
||||
TX_LED_ON;
|
||||
|
||||
PIOS_DELAY_WaitmS(200);
|
||||
}
|
||||
|
||||
PIOS_DELAY_WaitmS(1000);
|
||||
|
||||
return initval;
|
||||
}
|
||||
|
||||
rfm22_setFreqCalibration(cfg->RFXtalCap);
|
||||
rfm22_setNominalCarrierFrequency(cfg->frequencyHz);
|
||||
rfm22_setDatarate(cfg->maxRFBandwidth, TRUE);
|
||||
rfm22_setTxPower(cfg->maxTxPower);
|
||||
|
||||
DEBUG_PRINTF(2, "\n\r");
|
||||
DEBUG_PRINTF(2, "RF device ID: %x\n\r", rfm22b_dev->deviceID);
|
||||
DEBUG_PRINTF(2, "RF datarate: %dbps\n\r", rfm22_getDatarate());
|
||||
DEBUG_PRINTF(2, "RF frequency: %dHz\n\r", rfm22_getNominalCarrierFrequency());
|
||||
DEBUG_PRINTF(2, "RF TX power: %d\n\r", rfm22_getTxPower());
|
||||
|
||||
// Setup a real-time clock callback to kickstart the radio if a transfer lock sup.
|
||||
if (!PIOS_RTC_RegisterTickCallback(PIOS_RFM22B_Supervisor, *rfm22b_id)) {
|
||||
PIOS_DEBUG_Assert(0);
|
||||
}
|
||||
|
||||
return(0);
|
||||
}
|
||||
|
||||
uint32_t PIOS_RFM22B_DeviceID(uint32_t rfm22b_id)
|
||||
{
|
||||
struct pios_rfm22b_dev *rfm22b_dev = (struct pios_rfm22b_dev *)rfm22b_id;
|
||||
|
||||
return rfm22b_dev->deviceID;
|
||||
}
|
||||
|
||||
int8_t PIOS_RFM22B_RSSI(uint32_t rfm22b_id)
|
||||
{
|
||||
return rfm22_receivedRSSI();
|
||||
}
|
||||
|
||||
int16_t PIOS_RFM22B_Resets(uint32_t rfm22b_id)
|
||||
{
|
||||
struct pios_rfm22b_dev *rfm22b_dev = (struct pios_rfm22b_dev *)rfm22b_id;
|
||||
|
||||
return rfm22b_dev->resets;
|
||||
}
|
||||
|
||||
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);
|
||||
|
||||
}
|
||||
|
||||
static void PIOS_RFM22B_TxStart(uint32_t rfm22b_id, uint16_t tx_bytes_avail)
|
||||
{
|
||||
struct pios_rfm22b_dev * rfm22b_dev = (struct pios_rfm22b_dev *)rfm22b_id;
|
||||
bool valid = PIOS_RFM22B_validate(rfm22b_dev);
|
||||
PIOS_Assert(valid);
|
||||
|
||||
// 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);
|
||||
|
||||
if(tx_pre_buffer_size > 0)
|
||||
{
|
||||
|
||||
// already have data to be sent
|
||||
if (tx_data_wr > 0)
|
||||
return;
|
||||
|
||||
// we are currently transmitting or scanning the spectrum
|
||||
if (rf_mode == TX_DATA_MODE || rf_mode == TX_STREAM_MODE || rf_mode == TX_CARRIER_MODE ||
|
||||
rf_mode == TX_PN_MODE || rf_mode == RX_SCAN_SPECTRUM)
|
||||
return;
|
||||
|
||||
// is the channel clear to transmit on?
|
||||
if (!rfm22_channelIsClear())
|
||||
return;
|
||||
|
||||
// Start the transmit
|
||||
rfm22_txStart();
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* 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)
|
||||
{
|
||||
struct pios_rfm22b_dev * rfm22b_dev = (struct pios_rfm22b_dev *)rfm22b_id;
|
||||
|
||||
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;
|
||||
}
|
||||
|
||||
static void PIOS_RFM22B_Supervisor(uint32_t rfm22b_id)
|
||||
{
|
||||
/* Recover our device context */
|
||||
struct pios_rfm22b_dev * rfm22b_dev = (struct pios_rfm22b_dev *)rfm22b_id;
|
||||
|
||||
if (!PIOS_RFM22B_validate(rfm22b_dev)) {
|
||||
/* Invalid device specified */
|
||||
return;
|
||||
}
|
||||
|
||||
/* Not a problem if we're waiting for a packet. */
|
||||
if(rf_mode == RX_WAIT_SYNC_MODE)
|
||||
return;
|
||||
|
||||
/* The radio must be locked up if the timer reaches 0 */
|
||||
if(--(rfm22b_dev->supv_timer) != 0)
|
||||
return;
|
||||
++(rfm22b_dev->resets);
|
||||
|
||||
/* Start a packet transfer if one is available. */
|
||||
if(!rfm22_txStart())
|
||||
{
|
||||
/* Otherwise, switch to RX mode */
|
||||
rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false);
|
||||
}
|
||||
}
|
||||
|
||||
static void rfm22_setDebug(const char* msg)
|
||||
{
|
||||
debug_msg = msg;
|
||||
}
|
||||
|
||||
static void rfm22_setError(const char* msg)
|
||||
{
|
||||
error_msg = msg;
|
||||
}
|
||||
|
||||
// ************************************
|
||||
// SPI read/write
|
||||
|
||||
void rfm22_startBurstWrite(uint8_t addr)
|
||||
{
|
||||
// wait 1us .. so we don't toggle the CS line to quickly
|
||||
PIOS_DELAY_WaituS(1);
|
||||
|
||||
// chip select line LOW
|
||||
PIOS_SPI_RC_PinSet(RFM22_PIOS_SPI, 0, 0);
|
||||
|
||||
PIOS_SPI_TransferByte(RFM22_PIOS_SPI, 0x80 | addr);
|
||||
}
|
||||
|
||||
void rfm22_endBurstWrite(void)
|
||||
{
|
||||
// chip select line HIGH
|
||||
PIOS_SPI_RC_PinSet(RFM22_PIOS_SPI, 0, 1);
|
||||
}
|
||||
|
||||
void rfm22_write(uint8_t addr, uint8_t data)
|
||||
{
|
||||
// wait 1us .. so we don't toggle the CS line to quickly
|
||||
PIOS_DELAY_WaituS(1);
|
||||
|
||||
// chip select line LOW
|
||||
PIOS_SPI_RC_PinSet(RFM22_PIOS_SPI, 0, 0);
|
||||
|
||||
PIOS_SPI_TransferByte(RFM22_PIOS_SPI, 0x80 | addr);
|
||||
PIOS_SPI_TransferByte(RFM22_PIOS_SPI, data);
|
||||
|
||||
// chip select line HIGH
|
||||
PIOS_SPI_RC_PinSet(RFM22_PIOS_SPI, 0, 1);
|
||||
}
|
||||
|
||||
void rfm22_startBurstRead(uint8_t addr)
|
||||
{
|
||||
// wait 1us .. so we don't toggle the CS line to quickly
|
||||
PIOS_DELAY_WaituS(1);
|
||||
|
||||
// chip select line LOW
|
||||
PIOS_SPI_RC_PinSet(RFM22_PIOS_SPI, 0, 0);
|
||||
|
||||
PIOS_SPI_TransferByte(RFM22_PIOS_SPI, addr & 0x7f);
|
||||
}
|
||||
|
||||
void rfm22_endBurstRead(void)
|
||||
{
|
||||
// chip select line HIGH
|
||||
PIOS_SPI_RC_PinSet(RFM22_PIOS_SPI, 0, 1);
|
||||
}
|
||||
|
||||
uint8_t rfm22_read(uint8_t addr)
|
||||
{
|
||||
uint8_t rdata;
|
||||
|
||||
// wait 1us .. so we don't toggle the CS line to quickly
|
||||
PIOS_DELAY_WaituS(1);
|
||||
|
||||
// chip select line LOW
|
||||
PIOS_SPI_RC_PinSet(RFM22_PIOS_SPI, 0, 0);
|
||||
|
||||
PIOS_SPI_TransferByte(RFM22_PIOS_SPI, addr & 0x7f);
|
||||
rdata = PIOS_SPI_TransferByte(RFM22_PIOS_SPI, 0xff);
|
||||
|
||||
// chip select line HIGH
|
||||
PIOS_SPI_RC_PinSet(RFM22_PIOS_SPI, 0, 1);
|
||||
|
||||
return rdata;
|
||||
}
|
||||
|
||||
// ************************************
|
||||
// external interrupt
|
||||
|
||||
|
||||
static void PIOS_RFM22_EXT_Int(void)
|
||||
{
|
||||
rfm22_setDebug("Ext Int");
|
||||
if (!exec_using_spi)
|
||||
rfm22_processInt();
|
||||
rfm22_setDebug("Ext Done");
|
||||
}
|
||||
|
||||
void rfm22_disableExtInt(void)
|
||||
{
|
||||
#if defined(RFM22_EXT_INT_USE)
|
||||
rfm22_setDebug("Disable Int");
|
||||
// Configure the external interrupt
|
||||
GPIO_EXTILineConfig(PIOS_RFM22_EXTI_PORT_SOURCE, PIOS_RFM22_EXTI_PIN_SOURCE);
|
||||
EXTI_InitTypeDef EXTI_InitStructure = pios_exti_rfm22b_cfg.exti.init;
|
||||
EXTI_InitStructure.EXTI_LineCmd = DISABLE;
|
||||
EXTI_Init(&EXTI_InitStructure);
|
||||
|
||||
EXTI_ClearFlag(PIOS_RFM22_EXTI_LINE);
|
||||
rfm22_setDebug("Disable Int done");
|
||||
#endif
|
||||
}
|
||||
|
||||
void rfm22_enableExtInt(void)
|
||||
{
|
||||
#if defined(RFM22_EXT_INT_USE)
|
||||
rfm22_setDebug("Ensable Int");
|
||||
if (PIOS_EXTI_Init(&pios_exti_rfm22b_cfg))
|
||||
PIOS_Assert(0);
|
||||
rfm22_setDebug("Ensable Int done");
|
||||
#endif
|
||||
}
|
||||
|
||||
|
||||
// ************************************
|
||||
// set/get the current tx power setting
|
||||
|
||||
void rfm22_setTxPower(uint8_t tx_pwr)
|
||||
{
|
||||
switch (tx_pwr)
|
||||
{
|
||||
case 0: tx_power = RFM22_tx_pwr_txpow_0; break; // +1dBm ... 1.25mW
|
||||
case 1: tx_power = RFM22_tx_pwr_txpow_1; break; // +2dBm ... 1.6mW
|
||||
case 2: tx_power = RFM22_tx_pwr_txpow_2; break; // +5dBm ... 3.16mW
|
||||
case 3: tx_power = RFM22_tx_pwr_txpow_3; break; // +8dBm ... 6.3mW
|
||||
case 4: tx_power = RFM22_tx_pwr_txpow_4; break; // +11dBm .. 12.6mW
|
||||
case 5: tx_power = RFM22_tx_pwr_txpow_5; break; // +14dBm .. 25mW
|
||||
case 6: tx_power = RFM22_tx_pwr_txpow_6; break; // +17dBm .. 50mW
|
||||
case 7: tx_power = RFM22_tx_pwr_txpow_7; break; // +20dBm .. 100mW
|
||||
default: break;
|
||||
}
|
||||
}
|
||||
|
||||
uint8_t rfm22_getTxPower(void)
|
||||
{
|
||||
return tx_power;
|
||||
}
|
||||
|
||||
// ************************************
|
||||
|
||||
uint32_t rfm22_minFrequency(void)
|
||||
{
|
||||
return lower_carrier_frequency_limit_Hz;
|
||||
}
|
||||
uint32_t rfm22_maxFrequency(void)
|
||||
{
|
||||
return upper_carrier_frequency_limit_Hz;
|
||||
}
|
||||
|
||||
void rfm22_setNominalCarrierFrequency(uint32_t frequency_hz)
|
||||
{
|
||||
|
||||
exec_using_spi = TRUE;
|
||||
|
||||
// *******
|
||||
|
||||
if (frequency_hz < lower_carrier_frequency_limit_Hz) frequency_hz = lower_carrier_frequency_limit_Hz;
|
||||
else
|
||||
if (frequency_hz > upper_carrier_frequency_limit_Hz) frequency_hz = upper_carrier_frequency_limit_Hz;
|
||||
|
||||
if (frequency_hz < 480000000)
|
||||
hbsel = 1;
|
||||
else
|
||||
hbsel = 2;
|
||||
uint8_t fb = (uint8_t)(frequency_hz / (10000000 * hbsel));
|
||||
|
||||
uint32_t fc = (uint32_t)(frequency_hz - (10000000 * hbsel * fb));
|
||||
|
||||
fc = (fc * 64u) / (10000ul * hbsel);
|
||||
fb -= 24;
|
||||
|
||||
// carrier_frequency_hz = frequency_hz;
|
||||
carrier_frequency_hz = ((uint32_t)fb + 24 + ((float)fc / 64000)) * 10000000 * hbsel;
|
||||
|
||||
if (hbsel > 1)
|
||||
fb |= RFM22_fbs_hbsel;
|
||||
|
||||
fb |= RFM22_fbs_sbse; // is this the RX LO polarity?
|
||||
|
||||
frequency_step_size = 156.25f * hbsel;
|
||||
|
||||
rfm22_write(RFM22_frequency_hopping_channel_select, frequency_hop_channel); // frequency hopping channel (0-255)
|
||||
|
||||
rfm22_write(RFM22_frequency_offset1, 0); // no frequency offset
|
||||
rfm22_write(RFM22_frequency_offset2, 0); // no frequency offset
|
||||
|
||||
rfm22_write(RFM22_frequency_band_select, fb); // set the carrier frequency
|
||||
rfm22_write(RFM22_nominal_carrier_frequency1, fc >> 8); // " "
|
||||
rfm22_write(RFM22_nominal_carrier_frequency0, fc & 0xff); // " "
|
||||
|
||||
// *******
|
||||
|
||||
#if defined(RFM22_DEBUG)
|
||||
//DEBUG_PRINTF(2, "rf setFreq: %u\n\r", carrier_frequency_hz);
|
||||
// DEBUG_PRINTF(2, "rf setFreq frequency_step_size: %0.2f\n\r", frequency_step_size);
|
||||
#endif
|
||||
|
||||
exec_using_spi = FALSE;
|
||||
}
|
||||
|
||||
uint32_t rfm22_getNominalCarrierFrequency(void)
|
||||
{
|
||||
return carrier_frequency_hz;
|
||||
}
|
||||
|
||||
float rfm22_getFrequencyStepSize(void)
|
||||
{
|
||||
return frequency_step_size;
|
||||
}
|
||||
|
||||
void rfm22_setFreqHopChannel(uint8_t channel)
|
||||
{ // set the frequency hopping channel
|
||||
frequency_hop_channel = channel;
|
||||
rfm22_write(RFM22_frequency_hopping_channel_select, frequency_hop_channel);
|
||||
}
|
||||
|
||||
uint8_t rfm22_freqHopChannel(void)
|
||||
{ // return the current frequency hopping channel
|
||||
return frequency_hop_channel;
|
||||
}
|
||||
|
||||
uint32_t rfm22_freqHopSize(void)
|
||||
{ // return the frequency hopping step size
|
||||
return ((uint32_t)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 datarate_bps, bool data_whitening)
|
||||
{
|
||||
|
||||
exec_using_spi = TRUE;
|
||||
|
||||
lookup_index = 0;
|
||||
while (lookup_index < (LOOKUP_SIZE - 1) && data_rate[lookup_index] < datarate_bps)
|
||||
lookup_index++;
|
||||
|
||||
carrier_datarate_bps = datarate_bps = data_rate[lookup_index];
|
||||
|
||||
rf_bandwidth_used = rx_bandwidth[lookup_index];
|
||||
|
||||
// rfm22_if_filter_bandwidth
|
||||
rfm22_write(0x1C, reg_1C[lookup_index]);
|
||||
|
||||
// rfm22_afc_loop_gearshift_override
|
||||
rfm22_write(0x1D, reg_1D[lookup_index]);
|
||||
// RFM22_afc_timing_control
|
||||
rfm22_write(0x1E, reg_1E[lookup_index]);
|
||||
|
||||
// RFM22_clk_recovery_gearshift_override
|
||||
rfm22_write(0x1F, reg_1F[lookup_index]);
|
||||
// rfm22_clk_recovery_oversampling_ratio
|
||||
rfm22_write(0x20, reg_20[lookup_index]);
|
||||
// rfm22_clk_recovery_offset2
|
||||
rfm22_write(0x21, reg_21[lookup_index]);
|
||||
// rfm22_clk_recovery_offset1
|
||||
rfm22_write(0x22, reg_22[lookup_index]);
|
||||
// rfm22_clk_recovery_offset0
|
||||
rfm22_write(0x23, reg_23[lookup_index]);
|
||||
// rfm22_clk_recovery_timing_loop_gain1
|
||||
rfm22_write(0x24, reg_24[lookup_index]);
|
||||
// rfm22_clk_recovery_timing_loop_gain0
|
||||
rfm22_write(0x25, reg_25[lookup_index]);
|
||||
|
||||
// rfm22_afc_limiter
|
||||
rfm22_write(0x2A, reg_2A[lookup_index]);
|
||||
|
||||
if (carrier_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[lookup_index]);
|
||||
// rfm22_tx_data_rate0
|
||||
rfm22_write(0x6F, reg_6F[lookup_index]);
|
||||
|
||||
// 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[lookup_index] & ~RFM22_mmc1_enwhite);
|
||||
else
|
||||
// rfm22_modulation_mode_control1
|
||||
rfm22_write(0x70, reg_70[lookup_index] | RFM22_mmc1_enwhite);
|
||||
|
||||
// rfm22_modulation_mode_control2
|
||||
rfm22_write(0x71, reg_71[lookup_index]);
|
||||
|
||||
// rfm22_frequency_deviation
|
||||
rfm22_write(0x72, reg_72[lookup_index]);
|
||||
|
||||
rfm22_write(RFM22_ook_counter_value1, 0x00);
|
||||
rfm22_write(RFM22_ook_counter_value2, 0x00);
|
||||
|
||||
// ********************************
|
||||
// calculate the TX register values
|
||||
/*
|
||||
uint16_t fd = frequency_deviation / 625;
|
||||
|
||||
uint8_t mmc1 = RFM22_mmc1_enphpwdn | RFM22_mmc1_manppol;
|
||||
uint16_t txdr;
|
||||
if (datarate_bps < 30000)
|
||||
{
|
||||
txdr = (datarate_bps * 20972) / 10000;
|
||||
mmc1 |= RFM22_mmc1_txdtrtscale;
|
||||
}
|
||||
else
|
||||
txdr = (datarate_bps * 6553) / 100000;
|
||||
|
||||
uint8_t mmc2 = RFM22_mmc2_dtmod_fifo | RFM22_mmc2_modtyp_gfsk; // FIFO mode, GFSK
|
||||
// uint8_t mmc2 = RFM22_mmc2_dtmod_pn9 | RFM22_mmc2_modtyp_gfsk; // PN9 mode, GFSK .. TX TEST MODE
|
||||
if (fd & 0x100) mmc2 |= RFM22_mmc2_fd;
|
||||
|
||||
rfm22_write(RFM22_frequency_deviation, fd); // set the TX peak frequency deviation
|
||||
|
||||
rfm22_write(RFM22_modulation_mode_control1, mmc1);
|
||||
rfm22_write(RFM22_modulation_mode_control2, mmc2);
|
||||
|
||||
rfm22_write(RFM22_tx_data_rate1, txdr >> 8); // set the TX data rate
|
||||
rfm22_write(RFM22_tx_data_rate0, txdr); // " "
|
||||
*/
|
||||
// ********************************
|
||||
// determine a clear channel time
|
||||
|
||||
// initialise the stopwatch with a suitable resolution for the datarate
|
||||
//STOPWATCH_init(4000000ul / carrier_datarate_bps); // set resolution to the time for 1 nibble (4-bits) at rf datarate
|
||||
|
||||
// ********************************
|
||||
// determine suitable time-out periods
|
||||
|
||||
// milliseconds
|
||||
timeout_sync_ms = (8000ul * 16) / carrier_datarate_bps;
|
||||
if (timeout_sync_ms < 3)
|
||||
// because out timer resolution is only 1ms
|
||||
timeout_sync_ms = 3;
|
||||
|
||||
// milliseconds
|
||||
timeout_data_ms = (8000ul * 100) / carrier_datarate_bps;
|
||||
if (timeout_data_ms < 3)
|
||||
// because out timer resolution is only 1ms
|
||||
timeout_data_ms = 3;
|
||||
|
||||
// ********************************
|
||||
|
||||
#if defined(RFM22_DEBUG)
|
||||
/*
|
||||
DEBUG_PRINTF(2, "rf datarate_bps: %d\n\r", datarate_bps);
|
||||
DEBUG_PRINTF(2, "rf frequency_deviation: %d\n\r", frequency_deviation);
|
||||
uint32_t frequency_deviation = freq_deviation[lookup_index]; // Hz
|
||||
uint32_t modulation_bandwidth = datarate_bps + (2 * frequency_deviation);
|
||||
DEBUG_PRINTF(2, "rf modulation_bandwidth: %u\n\r", modulation_bandwidth);
|
||||
DEBUG_PRINTF(2, "rf_rx_bandwidth[%u]: %u\n\r", lookup_index, rx_bandwidth[lookup_index]);
|
||||
DEBUG_PRINTF(2, "rf est rx sensitivity[%u]: %ddBm\n\r", lookup_index, est_rx_sens_dBm[lookup_index]);
|
||||
*/
|
||||
#endif
|
||||
|
||||
// *******
|
||||
|
||||
exec_using_spi = FALSE;
|
||||
}
|
||||
|
||||
uint32_t rfm22_getDatarate(void)
|
||||
{
|
||||
return carrier_datarate_bps;
|
||||
}
|
||||
|
||||
// ************************************
|
||||
|
||||
void rfm22_setSSBandwidth(uint32_t bandwidth_index)
|
||||
{
|
||||
|
||||
exec_using_spi = TRUE;
|
||||
|
||||
ss_lookup_index = bandwidth_index;
|
||||
|
||||
ss_rf_bandwidth_used = ss_rx_bandwidth[lookup_index];
|
||||
|
||||
// ********************************
|
||||
|
||||
rfm22_write(0x1C, ss_reg_1C[ss_lookup_index]); // rfm22_if_filter_bandwidth
|
||||
rfm22_write(0x1D, ss_reg_1D[ss_lookup_index]); // rfm22_afc_loop_gearshift_override
|
||||
|
||||
rfm22_write(0x20, ss_reg_20[ss_lookup_index]); // rfm22_clk_recovery_oversampling_ratio
|
||||
rfm22_write(0x21, ss_reg_21[ss_lookup_index]); // rfm22_clk_recovery_offset2
|
||||
rfm22_write(0x22, ss_reg_22[ss_lookup_index]); // rfm22_clk_recovery_offset1
|
||||
rfm22_write(0x23, ss_reg_23[ss_lookup_index]); // rfm22_clk_recovery_offset0
|
||||
rfm22_write(0x24, ss_reg_24[ss_lookup_index]); // rfm22_clk_recovery_timing_loop_gain1
|
||||
rfm22_write(0x25, ss_reg_25[ss_lookup_index]); // rfm22_clk_recovery_timing_loop_gain0
|
||||
|
||||
rfm22_write(0x2A, ss_reg_2A[ss_lookup_index]); // rfm22_afc_limiter
|
||||
|
||||
rfm22_write(0x58, 0x80); // rfm22_chargepump_current_trimming_override
|
||||
|
||||
rfm22_write(0x70, ss_reg_70[ss_lookup_index]); // rfm22_modulation_mode_control1
|
||||
rfm22_write(0x71, ss_reg_71[ss_lookup_index]); // rfm22_modulation_mode_control2
|
||||
|
||||
rfm22_write(RFM22_ook_counter_value1, 0x00);
|
||||
rfm22_write(RFM22_ook_counter_value2, 0x00);
|
||||
|
||||
// ********************************
|
||||
|
||||
#if defined(RFM22_DEBUG)
|
||||
DEBUG_PRINTF(2, "ss_rf_rx_bandwidth[%u]: %u\n\r", ss_lookup_index, ss_rx_bandwidth[ss_lookup_index]);
|
||||
#endif
|
||||
|
||||
// *******
|
||||
|
||||
exec_using_spi = FALSE;
|
||||
}
|
||||
|
||||
// ************************************
|
||||
|
||||
void rfm22_setRxMode(uint8_t mode, bool multi_packet_mode)
|
||||
{
|
||||
exec_using_spi = TRUE;
|
||||
|
||||
// disable interrupts
|
||||
rfm22_write(RFM22_interrupt_enable1, 0x00);
|
||||
rfm22_write(RFM22_interrupt_enable2, 0x00);
|
||||
|
||||
// Switch to TUNE mode
|
||||
rfm22_write(RFM22_op_and_func_ctrl1, RFM22_opfc1_pllon);
|
||||
|
||||
RX_LED_OFF;
|
||||
TX_LED_OFF;
|
||||
|
||||
if (rf_mode == TX_CARRIER_MODE || rf_mode == TX_PN_MODE)
|
||||
{
|
||||
// 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 |
|
||||
RFM22_mmc2_modtyp_gfsk);
|
||||
}
|
||||
|
||||
// empty the rx buffer
|
||||
rx_buffer_wr = 0;
|
||||
// reset the timer
|
||||
rfm22_int_timer = 0;
|
||||
rf_mode = mode;
|
||||
|
||||
// Clear the TX buffer.
|
||||
tx_data_rd = tx_data_wr = 0;
|
||||
|
||||
// clear FIFOs
|
||||
if (!multi_packet_mode)
|
||||
{
|
||||
rfm22_write(RFM22_op_and_func_ctrl2, RFM22_opfc2_ffclrrx | RFM22_opfc2_ffclrtx);
|
||||
rfm22_write(RFM22_op_and_func_ctrl2, 0x00);
|
||||
} else {
|
||||
rfm22_write(RFM22_op_and_func_ctrl2, RFM22_opfc2_rxmpk | RFM22_opfc2_ffclrrx |
|
||||
RFM22_opfc2_ffclrtx);
|
||||
rfm22_write(RFM22_op_and_func_ctrl2, RFM22_opfc2_rxmpk);
|
||||
}
|
||||
|
||||
// enable RX interrupts
|
||||
rfm22_write(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_ie2_enswdet);
|
||||
|
||||
// enable the receiver
|
||||
// rfm22_write(RFM22_op_and_func_ctrl1, RFM22_opfc1_xton | RFM22_opfc1_rxon);
|
||||
rfm22_write(RFM22_op_and_func_ctrl1, RFM22_opfc1_pllon | RFM22_opfc1_rxon);
|
||||
|
||||
exec_using_spi = FALSE;
|
||||
}
|
||||
|
||||
// ************************************
|
||||
|
||||
uint16_t rfm22_addHeader()
|
||||
{
|
||||
uint16_t i = 0;
|
||||
|
||||
for (uint16_t j = (TX_PREAMBLE_NIBBLES + 1) / 2; j > 0; j--)
|
||||
{
|
||||
rfm22_burstWrite(PREAMBLE_BYTE);
|
||||
i++;
|
||||
}
|
||||
rfm22_burstWrite(SYNC_BYTE_1); i++;
|
||||
rfm22_burstWrite(SYNC_BYTE_2); i++;
|
||||
|
||||
return i;
|
||||
}
|
||||
|
||||
// ************************************
|
||||
|
||||
uint8_t rfm22_txStart()
|
||||
{
|
||||
if((tx_pre_buffer_size == 0) || (exec_using_spi == TRUE))
|
||||
{
|
||||
// Clear the TX buffer.
|
||||
tx_data_rd = tx_data_wr = 0;
|
||||
return 0;
|
||||
}
|
||||
|
||||
exec_using_spi = TRUE;
|
||||
|
||||
// Disable interrrupts.
|
||||
PIOS_IRQ_Disable();
|
||||
|
||||
// Initialize the supervisor timer.
|
||||
rfm22b_dev->supv_timer = PIOS_RFM22B_SUPERVISOR_TIMEOUT;
|
||||
|
||||
// disable interrupts
|
||||
rfm22_write(RFM22_interrupt_enable1, 0x00);
|
||||
rfm22_write(RFM22_interrupt_enable2, 0x00);
|
||||
|
||||
// TUNE mode
|
||||
rfm22_write(RFM22_op_and_func_ctrl1, RFM22_opfc1_pllon);
|
||||
|
||||
// Queue the data up for sending
|
||||
memcpy(tx_buffer, tx_pre_buffer, tx_pre_buffer_size);
|
||||
tx_data_rd = 0;
|
||||
tx_data_wr = tx_pre_buffer_size;
|
||||
tx_pre_buffer_size = 0;
|
||||
|
||||
RX_LED_OFF;
|
||||
|
||||
// Set the destination address in the transmit header.
|
||||
// The destination address is the first 4 bytes of the message.
|
||||
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]);
|
||||
|
||||
// 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 |
|
||||
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 | 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);
|
||||
|
||||
// *******************
|
||||
// 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, tx_data_wr);
|
||||
|
||||
// add some data
|
||||
rfm22_startBurstWrite(RFM22_fifo_access);
|
||||
for (uint16_t i = 0; (tx_data_rd < tx_data_wr) && (i < FIFO_SIZE); ++tx_data_rd, ++i)
|
||||
rfm22_burstWrite(tx_buffer[tx_data_rd]);
|
||||
rfm22_endBurstWrite();
|
||||
|
||||
// *******************
|
||||
|
||||
// reset the timer
|
||||
rfm22_int_timer = 0;
|
||||
|
||||
rf_mode = TX_DATA_MODE;
|
||||
|
||||
// enable TX interrupts
|
||||
// rfm22_write(RFM22_interrupt_enable1, RFM22_ie1_enpksent | RFM22_ie1_entxffaem | RFM22_ie1_enfferr);
|
||||
rfm22_write(RFM22_interrupt_enable1, RFM22_ie1_enpksent | RFM22_ie1_entxffaem);
|
||||
|
||||
// read interrupt status - clear interrupts
|
||||
//rfm22_read(RFM22_interrupt_status1);
|
||||
//rfm22_read(RFM22_interrupt_status2);
|
||||
|
||||
// enable the transmitter
|
||||
// rfm22_write(RFM22_op_and_func_ctrl1, RFM22_opfc1_xton | RFM22_opfc1_txon);
|
||||
rfm22_write(RFM22_op_and_func_ctrl1, RFM22_opfc1_pllon | RFM22_opfc1_txon);
|
||||
|
||||
// Re-ensable interrrupts.
|
||||
PIOS_IRQ_Enable();
|
||||
|
||||
TX_LED_ON;
|
||||
|
||||
exec_using_spi = FALSE;
|
||||
return 1;
|
||||
}
|
||||
|
||||
|
||||
static void rfm22_setTxMode(uint8_t mode)
|
||||
{
|
||||
rfm22_setDebug("setTxMode");
|
||||
if (mode != TX_DATA_MODE && mode != TX_STREAM_MODE && mode != TX_CARRIER_MODE && mode != TX_PN_MODE)
|
||||
return; // invalid mode
|
||||
|
||||
exec_using_spi = TRUE;
|
||||
|
||||
// *******************
|
||||
|
||||
// disable interrupts
|
||||
rfm22_write(RFM22_interrupt_enable1, 0x00);
|
||||
rfm22_write(RFM22_interrupt_enable2, 0x00);
|
||||
|
||||
// rfm22_write(RFM22_op_and_func_ctrl1, RFM22_opfc1_xton); // READY mode
|
||||
rfm22_write(RFM22_op_and_func_ctrl1, RFM22_opfc1_pllon); // TUNE mode
|
||||
|
||||
RX_LED_OFF;
|
||||
|
||||
// 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 | tx_power);
|
||||
|
||||
uint8_t fd_bit = rfm22_read(RFM22_modulation_mode_control2) & RFM22_mmc2_fd;
|
||||
if (mode == TX_CARRIER_MODE)
|
||||
// blank carrier mode - for testing
|
||||
rfm22_write(RFM22_modulation_mode_control2, fd_bit | RFM22_mmc2_dtmod_pn9 |
|
||||
RFM22_mmc2_modtyp_none); // FIFO mode, Blank carrier
|
||||
else if (mode == TX_PN_MODE)
|
||||
// psuedo random data carrier mode - for testing
|
||||
rfm22_write(RFM22_modulation_mode_control2, fd_bit | RFM22_mmc2_dtmod_pn9 |
|
||||
RFM22_mmc2_modtyp_gfsk); // FIFO mode, PN9 carrier
|
||||
else
|
||||
// data transmission
|
||||
// FIFO mode, GFSK modulation
|
||||
rfm22_write(RFM22_modulation_mode_control2, fd_bit | RFM22_mmc2_dtmod_fifo |
|
||||
RFM22_mmc2_modtyp_gfsk);
|
||||
|
||||
// rfm22_write(0x72, reg_72[lookup_index]); // rfm22_frequency_deviation
|
||||
|
||||
// clear FIFOs
|
||||
rfm22_write(RFM22_op_and_func_ctrl2, RFM22_opfc2_ffclrrx | RFM22_opfc2_ffclrtx);
|
||||
rfm22_write(RFM22_op_and_func_ctrl2, 0x00);
|
||||
|
||||
// *******************
|
||||
// add some data to the chips TX FIFO before enabling the transmitter
|
||||
{
|
||||
uint16_t rd = 0;
|
||||
uint16_t wr = tx_data_wr;
|
||||
|
||||
if (mode == TX_DATA_MODE)
|
||||
// set the total number of data bytes we are going to transmit
|
||||
rfm22_write(RFM22_transmit_packet_length, wr);
|
||||
|
||||
uint16_t max_bytes = FIFO_SIZE - 1;
|
||||
uint16_t i = 0;
|
||||
rfm22_startBurstWrite(RFM22_fifo_access);
|
||||
if (mode == TX_STREAM_MODE) {
|
||||
if (rd >= wr) {
|
||||
// no data to send - yet .. just send preamble pattern
|
||||
while (true) {
|
||||
rfm22_burstWrite(PREAMBLE_BYTE);
|
||||
if (++i >= max_bytes) break;
|
||||
}
|
||||
} else // add the RF heaader
|
||||
i += rfm22_addHeader();
|
||||
}
|
||||
|
||||
// add some data
|
||||
for (uint16_t j = wr - rd; j > 0; j--) {
|
||||
rfm22_burstWrite(tx_buffer[rd++]);
|
||||
if (++i >= max_bytes)
|
||||
break;
|
||||
}
|
||||
|
||||
rfm22_endBurstWrite();
|
||||
|
||||
tx_data_rd = rd;
|
||||
}
|
||||
|
||||
// *******************
|
||||
|
||||
// reset the timer
|
||||
rfm22_int_timer = 0;
|
||||
|
||||
rf_mode = mode;
|
||||
|
||||
// enable TX interrupts
|
||||
// rfm22_write(RFM22_interrupt_enable1, RFM22_ie1_enpksent | RFM22_ie1_entxffaem | RFM22_ie1_enfferr);
|
||||
rfm22_write(RFM22_interrupt_enable1, RFM22_ie1_enpksent | RFM22_ie1_entxffaem);
|
||||
|
||||
// read interrupt status - clear interrupts
|
||||
rfm22_read(RFM22_interrupt_status1);
|
||||
rfm22_read(RFM22_interrupt_status2);
|
||||
|
||||
// enable the transmitter
|
||||
// rfm22_write(RFM22_op_and_func_ctrl1, RFM22_opfc1_xton | RFM22_opfc1_txon);
|
||||
rfm22_write(RFM22_op_and_func_ctrl1, RFM22_opfc1_pllon | RFM22_opfc1_txon);
|
||||
|
||||
TX_LED_ON;
|
||||
|
||||
// *******************
|
||||
|
||||
exec_using_spi = FALSE;
|
||||
|
||||
rfm22_setDebug("setTxMode end");
|
||||
}
|
||||
|
||||
// ************************************
|
||||
// external interrupt line triggered (or polled) from the rf chip
|
||||
|
||||
void rfm22_processRxInt(void)
|
||||
{
|
||||
register uint8_t int_stat1 = int_status1;
|
||||
register uint8_t int_stat2 = int_status2;
|
||||
rfm22_setDebug("processRxInt");
|
||||
|
||||
// FIFO under/over flow error. Restart RX mode.
|
||||
if (device_status & (RFM22_ds_ffunfl | RFM22_ds_ffovfl))
|
||||
{
|
||||
rfm22_setError("R_UNDER/OVERRUN");
|
||||
rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false);
|
||||
return;
|
||||
}
|
||||
|
||||
// Sync timeout. Restart RX mode.
|
||||
if (rf_mode == RX_WAIT_SYNC_MODE && rfm22_int_timer >= timeout_sync_ms)
|
||||
{
|
||||
rfm22_int_time_outs++;
|
||||
rfm22_setError("R_SYNC_TIMEOUT");
|
||||
rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false);
|
||||
return;
|
||||
}
|
||||
|
||||
// RX timeout. Restart RX mode.
|
||||
if (rf_mode == RX_DATA_MODE && rfm22_int_timer >= timeout_data_ms)
|
||||
{
|
||||
rfm22_setError("MISSING_INTERRUPTS");
|
||||
rfm22_int_time_outs++;
|
||||
rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false);
|
||||
return;
|
||||
}
|
||||
|
||||
// The module is not in RX mode. Restart RX mode.
|
||||
if ((device_status & RFM22_ds_cps_mask) != RFM22_ds_cps_rx)
|
||||
{
|
||||
// the rf module is not in rx mode
|
||||
if (rfm22_int_timer >= 100)
|
||||
{
|
||||
rfm22_int_time_outs++;
|
||||
// reset the receiver
|
||||
rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false);
|
||||
return;
|
||||
}
|
||||
}
|
||||
|
||||
// Valid preamble detected
|
||||
if (int_stat2 & RFM22_is2_ipreaval)
|
||||
{
|
||||
if (rf_mode == RX_WAIT_PREAMBLE_MODE)
|
||||
{
|
||||
rfm22_int_timer = 0; // reset the timer
|
||||
rf_mode = RX_WAIT_SYNC_MODE;
|
||||
RX_LED_ON;
|
||||
rfm22_setDebug("pream_det");
|
||||
}
|
||||
}
|
||||
|
||||
// Sync word detected
|
||||
if (int_stat2 & RFM22_is2_iswdet)
|
||||
{
|
||||
if (rf_mode == RX_WAIT_PREAMBLE_MODE || rf_mode == RX_WAIT_SYNC_MODE)
|
||||
{
|
||||
rfm22_int_timer = 0; // reset the timer
|
||||
rf_mode = RX_DATA_MODE;
|
||||
RX_LED_ON;
|
||||
rfm22_setDebug("sync_det");
|
||||
|
||||
// read the 10-bit signed afc correction value
|
||||
// bits 9 to 2
|
||||
afc_correction = (uint16_t)rfm22_read(RFM22_afc_correction_read) << 8;
|
||||
// bits 1 & 0
|
||||
afc_correction |= (uint16_t)rfm22_read(RFM22_ook_counter_value1) & 0x00c0;
|
||||
afc_correction >>= 6;
|
||||
// convert the afc value to Hz
|
||||
afc_correction_Hz = (int32_t)(frequency_step_size * afc_correction + 0.5f);
|
||||
|
||||
// remember the rssi for this packet
|
||||
rx_packet_start_rssi_dBm = rssi_dBm;
|
||||
// remember the afc value for this packet
|
||||
rx_packet_start_afc_Hz = afc_correction_Hz;
|
||||
}
|
||||
}
|
||||
|
||||
// RX FIFO almost full, it needs emptying
|
||||
if (int_stat1 & RFM22_is1_irxffafull)
|
||||
{
|
||||
if (rf_mode == RX_DATA_MODE)
|
||||
{
|
||||
// read data from the rf chips FIFO buffer
|
||||
rfm22_int_timer = 0; // reset the timer
|
||||
|
||||
// read the total length of the packet data
|
||||
uint16_t len = rfm22_read(RFM22_received_packet_length);
|
||||
|
||||
// The received packet is going to be larger than the specified length
|
||||
if ((rx_buffer_wr + RX_FIFO_HI_WATERMARK) > len)
|
||||
{
|
||||
rfm22_setError("r_size_error1");
|
||||
rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false);
|
||||
return;
|
||||
}
|
||||
|
||||
// Another packet length error.
|
||||
if (((rx_buffer_wr + RX_FIFO_HI_WATERMARK) >= len) && !(int_stat1 & RFM22_is1_ipkvalid))
|
||||
{
|
||||
rfm22_setError("r_size_error2");
|
||||
rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false);
|
||||
return;
|
||||
}
|
||||
|
||||
// Fetch the data from the RX FIFO
|
||||
rfm22_startBurstRead(RFM22_fifo_access);
|
||||
for (uint8_t i = 0; i < RX_FIFO_HI_WATERMARK; ++i)
|
||||
rx_buffer[rx_buffer_wr++] = rfm22_burstRead();
|
||||
rfm22_endBurstRead();
|
||||
}
|
||||
else
|
||||
{ // just clear the RX FIFO
|
||||
rfm22_startBurstRead(RFM22_fifo_access);
|
||||
for (register uint16_t i = RX_FIFO_HI_WATERMARK; i > 0; i--)
|
||||
rfm22_burstRead(); // read a byte from the rf modules RX FIFO buffer
|
||||
rfm22_endBurstRead();
|
||||
}
|
||||
}
|
||||
|
||||
// CRC error .. discard the received data
|
||||
if (int_stat1 & RFM22_is1_icrerror)
|
||||
{
|
||||
rfm22_int_timer = 0; // reset the timer
|
||||
rfm22_setError("CRC_ERR");
|
||||
rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false);
|
||||
return;
|
||||
}
|
||||
|
||||
// if (int_stat2 & RFM22_is2_irssi)
|
||||
// { // RSSI level is >= the set threshold
|
||||
// }
|
||||
|
||||
// if (device_status & RFM22_ds_rxffem)
|
||||
// { // RX FIFO empty
|
||||
// }
|
||||
|
||||
// if (device_status & RFM22_ds_headerr)
|
||||
// { // Header check error
|
||||
// }
|
||||
|
||||
// Valid packet received
|
||||
if (int_stat1 & RFM22_is1_ipkvalid)
|
||||
{
|
||||
// reset the timer
|
||||
rfm22_int_timer = 0;
|
||||
|
||||
// read the total length of the packet data
|
||||
register uint16_t len = rfm22_read(RFM22_received_packet_length);
|
||||
|
||||
// their must still be data in the RX FIFO we need to get
|
||||
if (rx_buffer_wr < len)
|
||||
{
|
||||
// Fetch the data from the RX FIFO
|
||||
rfm22_startBurstRead(RFM22_fifo_access);
|
||||
while (rx_buffer_wr < len)
|
||||
rx_buffer[rx_buffer_wr++] = rfm22_burstRead();
|
||||
rfm22_endBurstRead();
|
||||
}
|
||||
|
||||
if (rx_buffer_wr != len)
|
||||
{
|
||||
// we have a packet length error .. discard the packet
|
||||
rfm22_setError("r_pack_len_error");
|
||||
debug_val = len;
|
||||
return;
|
||||
}
|
||||
|
||||
// we have a valid received packet
|
||||
rfm22_setDebug("VALID_R_PACKET");
|
||||
|
||||
if (rx_buffer_wr > 0)
|
||||
{
|
||||
// remember the rssi for this packet
|
||||
rx_packet_rssi_dBm = rx_packet_start_rssi_dBm;
|
||||
// remember the afc offset for this packet
|
||||
rx_packet_afc_Hz = rx_packet_start_afc_Hz;
|
||||
// Add the rssi and afc to the end of the packet.
|
||||
rx_buffer[rx_buffer_wr++] = rx_packet_start_rssi_dBm;
|
||||
rx_buffer[rx_buffer_wr++] = rx_packet_start_afc_Hz;
|
||||
// Pass this packet on
|
||||
bool need_yield = false;
|
||||
if (rfm22b_dev_g->rx_in_cb)
|
||||
(rfm22b_dev_g->rx_in_cb)(rfm22b_dev_g->rx_in_context, (uint8_t*)rx_buffer,
|
||||
rx_buffer_wr, NULL, &need_yield);
|
||||
rx_buffer_wr = 0;
|
||||
}
|
||||
|
||||
// Send a packet if it's available.
|
||||
if(!rfm22_txStart())
|
||||
{
|
||||
// Switch to RX mode
|
||||
rfm22_setDebug(" Set RX");
|
||||
rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false);
|
||||
}
|
||||
}
|
||||
|
||||
rfm22_setDebug("processRxInt end");
|
||||
}
|
||||
|
||||
void rfm22_processTxInt(void)
|
||||
{
|
||||
register uint8_t int_stat1 = int_status1;
|
||||
|
||||
// reset the timer
|
||||
rfm22_int_timer = 0;
|
||||
|
||||
// FIFO under/over flow error. Back to RX mode.
|
||||
if (device_status & (RFM22_ds_ffunfl | RFM22_ds_ffovfl))
|
||||
{
|
||||
rfm22_setError("T_UNDER/OVERRUN");
|
||||
rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false);
|
||||
return;
|
||||
}
|
||||
|
||||
// Transmit timeout. Abort the transmit.
|
||||
if (rfm22_int_timer >= timeout_data_ms)
|
||||
{
|
||||
rfm22_int_time_outs++;
|
||||
rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false);
|
||||
return;
|
||||
}
|
||||
|
||||
// the rf module is not in tx mode
|
||||
if ((device_status & RFM22_ds_cps_mask) != RFM22_ds_cps_tx)
|
||||
{
|
||||
if (rfm22_int_timer >= 100)
|
||||
{
|
||||
rfm22_int_time_outs++;
|
||||
rfm22_setError("T_TIMEOUT");
|
||||
rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false); // back to rx mode
|
||||
return;
|
||||
}
|
||||
}
|
||||
|
||||
// TX FIFO almost empty, it needs filling up
|
||||
if (int_stat1 & RFM22_is1_ixtffaem)
|
||||
{
|
||||
// top-up the rf chips TX FIFO buffer
|
||||
uint16_t max_bytes = FIFO_SIZE - TX_FIFO_LO_WATERMARK - 1;
|
||||
rfm22_startBurstWrite(RFM22_fifo_access);
|
||||
for (uint16_t i = 0; (tx_data_rd < tx_data_wr) && (i < max_bytes); ++i, ++tx_data_rd)
|
||||
rfm22_burstWrite(tx_buffer[tx_data_rd]);
|
||||
rfm22_endBurstWrite();
|
||||
}
|
||||
|
||||
// Packet has been sent
|
||||
if (int_stat1 & RFM22_is1_ipksent)
|
||||
{
|
||||
rfm22_setDebug(" T_Sent");
|
||||
|
||||
// Send another packet if it's available.
|
||||
if(!rfm22_txStart())
|
||||
{
|
||||
// Switch to RX mode
|
||||
rfm22_setDebug(" Set RX");
|
||||
rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false);
|
||||
return;
|
||||
}
|
||||
}
|
||||
|
||||
rfm22_setDebug("ProcessTxInt done");
|
||||
}
|
||||
|
||||
static void rfm22_processInt(void)
|
||||
{
|
||||
rfm22_setDebug("ProcessInt");
|
||||
// this is called from the external interrupt handler
|
||||
|
||||
if (!initialized || power_on_reset)
|
||||
// we haven't yet been initialized
|
||||
return;
|
||||
|
||||
exec_using_spi = TRUE;
|
||||
|
||||
// Reset the supervisor timer.
|
||||
rfm22b_dev->supv_timer = PIOS_RFM22B_SUPERVISOR_TIMEOUT;
|
||||
|
||||
// ********************************
|
||||
// read the RF modules current status registers
|
||||
|
||||
// read interrupt status registers - clears the interrupt line
|
||||
int_status1 = rfm22_read(RFM22_interrupt_status1);
|
||||
int_status2 = rfm22_read(RFM22_interrupt_status2);
|
||||
|
||||
// read device status register
|
||||
device_status = rfm22_read(RFM22_device_status);
|
||||
|
||||
// read ezmac status register
|
||||
ezmac_status = rfm22_read(RFM22_ezmac_status);
|
||||
|
||||
// Read the RSSI if we're in RX mode
|
||||
if (rf_mode != TX_DATA_MODE && rf_mode != TX_STREAM_MODE &&
|
||||
rf_mode != TX_CARRIER_MODE && rf_mode != TX_PN_MODE)
|
||||
{
|
||||
// read rx signal strength .. 45 = -100dBm, 205 = -20dBm
|
||||
rssi = rfm22_read(RFM22_rssi);
|
||||
// convert to dBm
|
||||
rssi_dBm = (int8_t)(rssi >> 1) - 122;
|
||||
|
||||
// calibrate the RSSI value (rf bandwidth appears to affect it)
|
||||
// if (rf_bandwidth_used > 0)
|
||||
// rssi_dBm -= 10000 / rf_bandwidth_used;
|
||||
}
|
||||
else
|
||||
{
|
||||
// read the tx power register
|
||||
tx_pwr = rfm22_read(RFM22_tx_power);
|
||||
}
|
||||
|
||||
// the RF module has gone and done a reset - we need to re-initialize the rf module
|
||||
if (int_status2 & RFM22_is2_ipor)
|
||||
{
|
||||
initialized = FALSE;
|
||||
power_on_reset = TRUE;
|
||||
rfm22_setError("Reset");
|
||||
// Need to do something here!
|
||||
return;
|
||||
}
|
||||
|
||||
switch (rf_mode)
|
||||
{
|
||||
case RX_SCAN_SPECTRUM:
|
||||
break;
|
||||
|
||||
case RX_WAIT_PREAMBLE_MODE:
|
||||
case RX_WAIT_SYNC_MODE:
|
||||
case RX_DATA_MODE:
|
||||
|
||||
rfm22_processRxInt();
|
||||
break;
|
||||
|
||||
case TX_DATA_MODE:
|
||||
case TX_STREAM_MODE:
|
||||
|
||||
rfm22_processTxInt();
|
||||
break;
|
||||
|
||||
case TX_CARRIER_MODE:
|
||||
case TX_PN_MODE:
|
||||
|
||||
// if (rfm22_int_timer >= TX_TEST_MODE_TIMELIMIT_MS) // 'nn'ms limit
|
||||
// {
|
||||
// rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false); // back to rx mode
|
||||
// tx_data_rd = tx_data_wr = 0; // wipe TX buffer
|
||||
// break;
|
||||
// }
|
||||
|
||||
break;
|
||||
|
||||
default: // unknown mode - this should NEVER happen, maybe we should do a complete CPU reset here
|
||||
rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false); // to rx mode
|
||||
break;
|
||||
}
|
||||
|
||||
exec_using_spi = FALSE;
|
||||
|
||||
rfm22_setDebug("ProcessInt done");
|
||||
}
|
||||
|
||||
// ************************************
|
||||
|
||||
int8_t rfm22_getRSSI(void)
|
||||
{
|
||||
exec_using_spi = TRUE;
|
||||
|
||||
rssi = rfm22_read(RFM22_rssi); // read rx signal strength .. 45 = -100dBm, 205 = -20dBm
|
||||
rssi_dBm = (int8_t)(rssi >> 1) - 122; // convert to dBm
|
||||
|
||||
exec_using_spi = FALSE;
|
||||
return rssi_dBm;
|
||||
}
|
||||
|
||||
int8_t rfm22_receivedRSSI(void)
|
||||
{ // return the packets signal strength
|
||||
if (!initialized)
|
||||
return -127;
|
||||
else
|
||||
return rx_packet_rssi_dBm;
|
||||
}
|
||||
|
||||
int32_t rfm22_receivedAFCHz(void)
|
||||
{ // return the packets offset frequency
|
||||
if (!initialized)
|
||||
return 0;
|
||||
else
|
||||
return rx_packet_afc_Hz;
|
||||
}
|
||||
|
||||
// ************************************
|
||||
|
||||
// ************************************
|
||||
|
||||
void rfm22_setTxStream(void) // TEST ONLY
|
||||
{
|
||||
if (!initialized)
|
||||
return;
|
||||
|
||||
tx_data_rd = tx_data_wr = 0;
|
||||
|
||||
rfm22_setTxMode(TX_STREAM_MODE);
|
||||
}
|
||||
|
||||
// ************************************
|
||||
|
||||
void rfm22_setTxNormal(void)
|
||||
{
|
||||
if (!initialized)
|
||||
return;
|
||||
|
||||
// if (rf_mode == TX_CARRIER_MODE || rf_mode == TX_PN_MODE)
|
||||
if (rf_mode != RX_SCAN_SPECTRUM)
|
||||
{
|
||||
rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false);
|
||||
tx_data_rd = tx_data_wr = 0;
|
||||
|
||||
rx_packet_start_rssi_dBm = 0;
|
||||
rx_packet_start_afc_Hz = 0;
|
||||
rx_packet_rssi_dBm = 0;
|
||||
rx_packet_afc_Hz = 0;
|
||||
}
|
||||
}
|
||||
|
||||
// enable a blank tx carrier (for frequency alignment)
|
||||
void rfm22_setTxCarrierMode(void)
|
||||
{
|
||||
if (!initialized)
|
||||
return;
|
||||
|
||||
if (rf_mode != TX_CARRIER_MODE && rf_mode != RX_SCAN_SPECTRUM)
|
||||
rfm22_setTxMode(TX_CARRIER_MODE);
|
||||
}
|
||||
|
||||
// enable a psuedo random data tx carrier (for spectrum inspection)
|
||||
void rfm22_setTxPNMode(void)
|
||||
{
|
||||
if (!initialized)
|
||||
return;
|
||||
|
||||
if (rf_mode != TX_PN_MODE && rf_mode != RX_SCAN_SPECTRUM)
|
||||
rfm22_setTxMode(TX_PN_MODE);
|
||||
}
|
||||
|
||||
// ************************************
|
||||
|
||||
// return the current mode
|
||||
int8_t rfm22_currentMode(void)
|
||||
{
|
||||
return rf_mode;
|
||||
}
|
||||
|
||||
// return TRUE if we are transmitting
|
||||
bool rfm22_transmitting(void)
|
||||
{
|
||||
return (rf_mode == TX_DATA_MODE || rf_mode == TX_STREAM_MODE || rf_mode == TX_CARRIER_MODE || rf_mode == TX_PN_MODE);
|
||||
}
|
||||
|
||||
// return TRUE if the channel is clear to transmit on
|
||||
bool rfm22_channelIsClear(void)
|
||||
{
|
||||
if (!initialized)
|
||||
// we haven't yet been initialized
|
||||
return FALSE;
|
||||
|
||||
if (rf_mode != RX_WAIT_PREAMBLE_MODE && rf_mode != RX_WAIT_SYNC_MODE)
|
||||
// we are receiving something or we are transmitting or we are scanning the spectrum
|
||||
return FALSE;
|
||||
|
||||
return TRUE;
|
||||
}
|
||||
|
||||
// return TRUE if the transmiter is ready for use
|
||||
bool rfm22_txReady(void)
|
||||
{
|
||||
if (!initialized)
|
||||
// we haven't yet been initialized
|
||||
return FALSE;
|
||||
|
||||
return (tx_data_rd == 0 && tx_data_wr == 0 && rf_mode != TX_DATA_MODE &&
|
||||
rf_mode != TX_STREAM_MODE && rf_mode != TX_CARRIER_MODE && rf_mode != TX_PN_MODE &&
|
||||
rf_mode != RX_SCAN_SPECTRUM);
|
||||
}
|
||||
|
||||
// ************************************
|
||||
// set/get the frequency calibration value
|
||||
|
||||
void rfm22_setFreqCalibration(uint8_t value)
|
||||
{
|
||||
osc_load_cap = value;
|
||||
|
||||
if (!initialized || power_on_reset)
|
||||
return; // we haven't yet been initialized
|
||||
|
||||
uint8_t prev_rf_mode = rf_mode;
|
||||
|
||||
if (rf_mode == TX_CARRIER_MODE || rf_mode == TX_PN_MODE)
|
||||
{
|
||||
rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false);
|
||||
tx_data_rd = tx_data_wr = 0;
|
||||
}
|
||||
|
||||
exec_using_spi = TRUE;
|
||||
|
||||
rfm22_write(RFM22_xtal_osc_load_cap, osc_load_cap);
|
||||
|
||||
exec_using_spi = FALSE;
|
||||
|
||||
if (prev_rf_mode == TX_CARRIER_MODE || prev_rf_mode == TX_PN_MODE)
|
||||
rfm22_setTxMode(prev_rf_mode);
|
||||
}
|
||||
|
||||
uint8_t rfm22_getFreqCalibration(void)
|
||||
{
|
||||
return osc_load_cap;
|
||||
}
|
||||
|
||||
// ************************************
|
||||
// can be called from an interrupt if you wish
|
||||
|
||||
void rfm22_1ms_tick(void)
|
||||
{ // call this once every ms
|
||||
if (!initialized) return; // we haven't yet been initialized
|
||||
|
||||
if (rf_mode != RX_SCAN_SPECTRUM)
|
||||
{
|
||||
if (rfm22_int_timer < 0xffff) rfm22_int_timer++;
|
||||
}
|
||||
}
|
||||
|
||||
// ************************************
|
||||
// reset the RF module
|
||||
|
||||
int rfm22_resetModule(uint8_t mode, uint32_t min_frequency_hz, uint32_t max_frequency_hz)
|
||||
{
|
||||
initialized = false;
|
||||
|
||||
#if defined(RFM22_EXT_INT_USE)
|
||||
rfm22_disableExtInt();
|
||||
#endif
|
||||
|
||||
power_on_reset = false;
|
||||
|
||||
// ****************
|
||||
|
||||
exec_using_spi = TRUE;
|
||||
|
||||
// ****************
|
||||
// setup the SPI port
|
||||
|
||||
// chip select line HIGH
|
||||
PIOS_SPI_RC_PinSet(RFM22_PIOS_SPI, 0, 1);
|
||||
|
||||
// set SPI port SCLK frequency .. 4.5MHz
|
||||
PIOS_SPI_SetClockSpeed(RFM22_PIOS_SPI, PIOS_SPI_PRESCALER_16);
|
||||
// set SPI port SCLK frequency .. 2.25MHz
|
||||
// PIOS_SPI_SetClockSpeed(RFM22_PIOS_SPI, PIOS_SPI_PRESCALER_32);
|
||||
|
||||
// set SPI port SCLK frequency .. 285kHz .. purely for hardware fault finding
|
||||
// PIOS_SPI_SetClockSpeed(RFM22_PIOS_SPI, PIOS_SPI_PRESCALER_256);
|
||||
|
||||
// ****************
|
||||
// software reset the RF chip .. following procedure according to Si4x3x Errata (rev. B)
|
||||
|
||||
rfm22_write(RFM22_op_and_func_ctrl1, RFM22_opfc1_swres); // software reset the radio
|
||||
|
||||
PIOS_DELAY_WaitmS(26); // wait 26ms
|
||||
|
||||
for (int i = 50; i > 0; i--)
|
||||
{
|
||||
PIOS_DELAY_WaitmS(1); // wait 1ms
|
||||
|
||||
// read the status registers
|
||||
int_status1 = rfm22_read(RFM22_interrupt_status1);
|
||||
int_status2 = rfm22_read(RFM22_interrupt_status2);
|
||||
if (int_status2 & RFM22_is2_ichiprdy) break;
|
||||
}
|
||||
|
||||
// ****************
|
||||
|
||||
// read status - clears interrupt
|
||||
device_status = rfm22_read(RFM22_device_status);
|
||||
int_status1 = rfm22_read(RFM22_interrupt_status1);
|
||||
int_status2 = rfm22_read(RFM22_interrupt_status2);
|
||||
ezmac_status = rfm22_read(RFM22_ezmac_status);
|
||||
|
||||
// disable all interrupts
|
||||
rfm22_write(RFM22_interrupt_enable1, 0x00);
|
||||
rfm22_write(RFM22_interrupt_enable2, 0x00);
|
||||
|
||||
// ****************
|
||||
|
||||
exec_using_spi = FALSE;
|
||||
|
||||
// ****************
|
||||
|
||||
rf_mode = mode;
|
||||
|
||||
device_status = int_status1 = int_status2 = ezmac_status = 0;
|
||||
|
||||
rssi = 0;
|
||||
rssi_dBm = -127;
|
||||
|
||||
rx_buffer_current = 0;
|
||||
rx_buffer_wr = 0;
|
||||
rx_packet_rssi_dBm = -127;
|
||||
rx_packet_afc_Hz = 0;
|
||||
|
||||
tx_data_rd = tx_data_wr = 0;
|
||||
|
||||
lookup_index = 0;
|
||||
ss_lookup_index = 0;
|
||||
|
||||
rf_bandwidth_used = 0;
|
||||
ss_rf_bandwidth_used = 0;
|
||||
|
||||
rfm22_int_timer = 0;
|
||||
rfm22_int_time_outs = 0;
|
||||
prev_rfm22_int_time_outs = 0;
|
||||
|
||||
hbsel = 0;
|
||||
frequency_step_size = 0.0f;
|
||||
|
||||
frequency_hop_channel = 0;
|
||||
|
||||
afc_correction = 0;
|
||||
afc_correction_Hz = 0;
|
||||
|
||||
temperature_reg = 0;
|
||||
|
||||
// set the TX power
|
||||
tx_power = RFM22_DEFAULT_RF_POWER;
|
||||
|
||||
tx_pwr = 0;
|
||||
|
||||
// ****************
|
||||
// read the RF chip ID bytes
|
||||
|
||||
device_type = rfm22_read(RFM22_DEVICE_TYPE) & RFM22_DT_MASK; // read the device type
|
||||
device_version = rfm22_read(RFM22_DEVICE_VERSION) & RFM22_DV_MASK; // read the device version
|
||||
|
||||
#if defined(RFM22_DEBUG)
|
||||
DEBUG_PRINTF(2, "rf device type: %d\n\r", device_type);
|
||||
DEBUG_PRINTF(2, "rf device version: %d\n\r", device_version);
|
||||
#endif
|
||||
|
||||
if (device_type != 0x08)
|
||||
{
|
||||
#if defined(RFM22_DEBUG)
|
||||
DEBUG_PRINTF(2, "rf device type: INCORRECT - should be 0x08\n\r");
|
||||
#endif
|
||||
return -1; // incorrect RF module type
|
||||
}
|
||||
|
||||
// if (device_version != RFM22_DEVICE_VERSION_V2) // V2
|
||||
// return -2; // incorrect RF module version
|
||||
// if (device_version != RFM22_DEVICE_VERSION_A0) // A0
|
||||
// return -2; // incorrect RF module version
|
||||
if (device_version != RFM22_DEVICE_VERSION_B1) // B1
|
||||
{
|
||||
#if defined(RFM22_DEBUG)
|
||||
DEBUG_PRINTF(2, "rf device version: INCORRECT\n\r");
|
||||
#endif
|
||||
return -2; // incorrect RF module version
|
||||
}
|
||||
|
||||
// ****************
|
||||
// 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;
|
||||
}
|
||||
|
||||
lower_carrier_frequency_limit_Hz = min_frequency_hz;
|
||||
upper_carrier_frequency_limit_Hz = max_frequency_hz;
|
||||
|
||||
// ****************
|
||||
// calibrate our RF module to be exactly on frequency .. different for every module
|
||||
|
||||
osc_load_cap = OSC_LOAD_CAP; // default
|
||||
rfm22_write(RFM22_xtal_osc_load_cap, osc_load_cap);
|
||||
|
||||
// ****************
|
||||
|
||||
// disable Low Duty Cycle Mode
|
||||
rfm22_write(RFM22_op_and_func_ctrl2, 0x00);
|
||||
|
||||
rfm22_write(RFM22_cpu_output_clk, RFM22_coc_1MHz); // 1MHz clock output
|
||||
|
||||
rfm22_write(RFM22_op_and_func_ctrl1, RFM22_opfc1_xton); // READY mode
|
||||
// rfm22_write(RFM22_op_and_func_ctrl1, RFM22_opfc1_pllon); // TUNE mode
|
||||
|
||||
// choose the 3 GPIO pin functions
|
||||
rfm22_write(RFM22_io_port_config, RFM22_io_port_default); // GPIO port use default value
|
||||
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(RFM22_gpio2_config, RFM22_gpio2_config_drv3 | RFM22_gpio2_config_cca); // GPIO2 = Clear Channel Assessment
|
||||
|
||||
// ****************
|
||||
|
||||
return 0; // OK
|
||||
}
|
||||
|
||||
// ************************************
|
||||
|
||||
int rfm22_init_scan_spectrum(uint32_t min_frequency_hz, uint32_t max_frequency_hz)
|
||||
{
|
||||
#if defined(RFM22_DEBUG)
|
||||
DEBUG_PRINTF(2, "\n\rRF init scan spectrum\n\r");
|
||||
#endif
|
||||
|
||||
int res = rfm22_resetModule(RX_SCAN_SPECTRUM, min_frequency_hz, max_frequency_hz);
|
||||
if (res < 0)
|
||||
return res;
|
||||
|
||||
// rfm22_setSSBandwidth(0);
|
||||
rfm22_setSSBandwidth(1);
|
||||
|
||||
// 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);
|
||||
|
||||
rfm22_write(RFM22_cpu_output_clk, RFM22_coc_1MHz); // 1MHz clock output
|
||||
|
||||
rfm22_write(RFM22_rssi_threshold_clear_chan_indicator, 0);
|
||||
|
||||
rfm22_write(RFM22_preamble_detection_ctrl1, 31 << 3); // 31-nibbles rx preamble detection
|
||||
|
||||
// avoid packet detection
|
||||
rfm22_write(RFM22_data_access_control, RFM22_dac_enpacrx | RFM22_dac_encrc);
|
||||
rfm22_write(RFM22_header_control1, 0x0f);
|
||||
rfm22_write(RFM22_header_control2, 0x77);
|
||||
|
||||
rfm22_write(RFM22_sync_word3, SYNC_BYTE_1);
|
||||
rfm22_write(RFM22_sync_word2, SYNC_BYTE_2);
|
||||
rfm22_write(RFM22_sync_word1, SYNC_BYTE_3 ^ 0xff);
|
||||
rfm22_write(RFM22_sync_word0, SYNC_BYTE_4 ^ 0xff);
|
||||
|
||||
// all the bits to be checked
|
||||
rfm22_write(RFM22_header_enable3, 0xff);
|
||||
rfm22_write(RFM22_header_enable2, 0xff);
|
||||
rfm22_write(RFM22_header_enable1, 0xff);
|
||||
rfm22_write(RFM22_header_enable0, 0xff);
|
||||
|
||||
// set frequency hopping channel step size (multiples of 10kHz)
|
||||
// rfm22_write(RFM22_frequency_hopping_step_size, 0);
|
||||
|
||||
// set our nominal carrier frequency
|
||||
rfm22_setNominalCarrierFrequency(min_frequency_hz);
|
||||
|
||||
// set minimum tx power
|
||||
rfm22_write(RFM22_tx_power, RFM22_tx_pwr_lna_sw | 0);
|
||||
|
||||
rfm22_write(RFM22_agc_override1, RFM22_agc_ovr1_sgi | RFM22_agc_ovr1_agcen);
|
||||
|
||||
// rfm22_write(RFM22_vco_current_trimming, 0x7f);
|
||||
// rfm22_write(RFM22_vco_calibration_override, 0x40);
|
||||
// rfm22_write(RFM22_chargepump_current_trimming_override, 0x80);
|
||||
|
||||
// Enable RF module external interrupt
|
||||
rfm22_enableExtInt();
|
||||
|
||||
rfm22_setRxMode(RX_SCAN_SPECTRUM, true);
|
||||
|
||||
initialized = true;
|
||||
|
||||
return 0; // OK
|
||||
}
|
||||
|
||||
// ************************************
|
||||
|
||||
int rfm22_init_tx_stream(uint32_t min_frequency_hz, uint32_t max_frequency_hz)
|
||||
{
|
||||
#if defined(RFM22_DEBUG)
|
||||
DEBUG_PRINTF(2, "\n\rRF init TX stream\n\r");
|
||||
#endif
|
||||
|
||||
int res = rfm22_resetModule(TX_STREAM_MODE, min_frequency_hz, max_frequency_hz);
|
||||
if (res < 0)
|
||||
return res;
|
||||
|
||||
frequency_hop_step_size_reg = 0;
|
||||
|
||||
// set the RF datarate
|
||||
rfm22_setDatarate(RFM22_DEFAULT_RF_DATARATE, FALSE);
|
||||
|
||||
// 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);
|
||||
|
||||
// disable the internal Tx & Rx packet handlers (without CRC)
|
||||
rfm22_write(RFM22_data_access_control, 0);
|
||||
|
||||
rfm22_write(RFM22_preamble_length, TX_PREAMBLE_NIBBLES); // x-nibbles tx preamble
|
||||
rfm22_write(RFM22_preamble_detection_ctrl1, RX_PREAMBLE_NIBBLES << 3); // x-nibbles rx preamble detection
|
||||
|
||||
rfm22_write(RFM22_header_control1, RFM22_header_cntl1_bcen_none | RFM22_header_cntl1_hdch_none); // header control - we are not using the header
|
||||
rfm22_write(RFM22_header_control2, RFM22_header_cntl2_fixpklen | RFM22_header_cntl2_hdlen_none | RFM22_header_cntl2_synclen_32 | ((TX_PREAMBLE_NIBBLES >> 8) & 0x01)); // no header bytes, synchronization word length 3, 2 used, packet length not included in header (fixed packet length).
|
||||
|
||||
rfm22_write(RFM22_sync_word3, SYNC_BYTE_1); // sync word
|
||||
rfm22_write(RFM22_sync_word2, SYNC_BYTE_2); //
|
||||
|
||||
// rfm22_write(RFM22_modem_test, 0x01);
|
||||
|
||||
rfm22_write(RFM22_agc_override1, RFM22_agc_ovr1_agcen);
|
||||
// rfm22_write(RFM22_agc_override1, RFM22_agc_ovr1_sgi | RFM22_agc_ovr1_agcen);
|
||||
|
||||
rfm22_write(RFM22_frequency_hopping_step_size, frequency_hop_step_size_reg); // set frequency hopping channel step size (multiples of 10kHz)
|
||||
|
||||
rfm22_setNominalCarrierFrequency((min_frequency_hz + max_frequency_hz) / 2); // set our nominal carrier frequency
|
||||
|
||||
rfm22_write(RFM22_tx_power, RFM22_tx_pwr_papeaken | RFM22_tx_pwr_papeaklvl_0 | RFM22_tx_pwr_lna_sw | tx_power); // set the tx power
|
||||
// rfm22_write(RFM22_tx_power, RFM22_tx_pwr_lna_sw | tx_power); // set the tx power
|
||||
|
||||
// rfm22_write(RFM22_vco_current_trimming, 0x7f);
|
||||
// rfm22_write(RFM22_vco_calibration_override, 0x40);
|
||||
// rfm22_write(RFM22_chargepump_current_trimming_override, 0x80);
|
||||
|
||||
rfm22_write(RFM22_tx_fifo_control1, TX_FIFO_HI_WATERMARK); // TX FIFO Almost Full Threshold (0 - 63)
|
||||
rfm22_write(RFM22_tx_fifo_control2, TX_FIFO_LO_WATERMARK); // TX FIFO Almost Empty Threshold (0 - 63)
|
||||
|
||||
// Enable RF module external interrupt
|
||||
rfm22_enableExtInt();
|
||||
|
||||
initialized = true;
|
||||
|
||||
return 0; // OK
|
||||
}
|
||||
|
||||
// ************************************
|
||||
|
||||
int rfm22_init_rx_stream(uint32_t min_frequency_hz, uint32_t max_frequency_hz)
|
||||
{
|
||||
#if defined(RFM22_DEBUG)
|
||||
DEBUG_PRINTF(2, "\n\rRF init RX stream\n\r");
|
||||
#endif
|
||||
|
||||
int res = rfm22_resetModule(RX_WAIT_PREAMBLE_MODE, min_frequency_hz, max_frequency_hz);
|
||||
if (res < 0)
|
||||
return res;
|
||||
|
||||
frequency_hop_step_size_reg = 0;
|
||||
|
||||
// set the RF datarate
|
||||
rfm22_setDatarate(RFM22_DEFAULT_RF_DATARATE, FALSE);
|
||||
|
||||
// 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);
|
||||
|
||||
// disable the internal Tx & Rx packet handlers (without CRC)
|
||||
rfm22_write(RFM22_data_access_control, 0);
|
||||
|
||||
rfm22_write(RFM22_preamble_length, TX_PREAMBLE_NIBBLES); // x-nibbles tx preamble
|
||||
rfm22_write(RFM22_preamble_detection_ctrl1, RX_PREAMBLE_NIBBLES << 3); // x-nibbles rx preamble detection
|
||||
|
||||
rfm22_write(RFM22_header_control1, RFM22_header_cntl1_bcen_none | RFM22_header_cntl1_hdch_none); // header control - we are not using the header
|
||||
rfm22_write(RFM22_header_control2, RFM22_header_cntl2_fixpklen | RFM22_header_cntl2_hdlen_none | RFM22_header_cntl2_synclen_32 | ((TX_PREAMBLE_NIBBLES >> 8) & 0x01)); // no header bytes, synchronization word length 3, 2 used, packet length not included in header (fixed packet length).
|
||||
|
||||
rfm22_write(RFM22_sync_word3, SYNC_BYTE_1); // sync word
|
||||
rfm22_write(RFM22_sync_word2, SYNC_BYTE_2); //
|
||||
|
||||
// no header bits to be checked
|
||||
rfm22_write(RFM22_header_enable3, 0x00);
|
||||
rfm22_write(RFM22_header_enable2, 0x00);
|
||||
rfm22_write(RFM22_header_enable1, 0x00);
|
||||
rfm22_write(RFM22_header_enable0, 0x00);
|
||||
|
||||
// rfm22_write(RFM22_modem_test, 0x01);
|
||||
|
||||
rfm22_write(RFM22_agc_override1, RFM22_agc_ovr1_agcen);
|
||||
// rfm22_write(RFM22_agc_override1, RFM22_agc_ovr1_sgi | RFM22_agc_ovr1_agcen);
|
||||
|
||||
rfm22_write(RFM22_frequency_hopping_step_size, frequency_hop_step_size_reg); // set frequency hopping channel step size (multiples of 10kHz)
|
||||
|
||||
rfm22_setNominalCarrierFrequency((min_frequency_hz + max_frequency_hz) / 2); // set our nominal carrier frequency
|
||||
|
||||
// rfm22_write(RFM22_vco_current_trimming, 0x7f);
|
||||
// rfm22_write(RFM22_vco_calibration_override, 0x40);
|
||||
// rfm22_write(RFM22_chargepump_current_trimming_override, 0x80);
|
||||
|
||||
// RX FIFO Almost Full Threshold (0 - 63)
|
||||
rfm22_write(RFM22_rx_fifo_control, RX_FIFO_HI_WATERMARK);
|
||||
|
||||
// Enable RF module external interrupt
|
||||
rfm22_enableExtInt();
|
||||
|
||||
rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false);
|
||||
|
||||
initialized = true;
|
||||
|
||||
return 0; // OK
|
||||
}
|
||||
|
||||
// ************************************
|
||||
// Initialise this hardware layer module and the rf module
|
||||
|
||||
int rfm22_init_normal(uint32_t id, uint32_t min_frequency_hz, uint32_t max_frequency_hz, uint32_t freq_hop_step_size)
|
||||
{
|
||||
int res = rfm22_resetModule(RX_WAIT_PREAMBLE_MODE, min_frequency_hz, max_frequency_hz);
|
||||
if (res < 0)
|
||||
return res;
|
||||
|
||||
// initialize the frequency hopping step size
|
||||
freq_hop_step_size /= 10000; // in 10kHz increments
|
||||
if (freq_hop_step_size > 255) freq_hop_step_size = 255;
|
||||
frequency_hop_step_size_reg = freq_hop_step_size;
|
||||
|
||||
// set the RF datarate
|
||||
rfm22_setDatarate(RFM22_DEFAULT_RF_DATARATE, TRUE);
|
||||
|
||||
// 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);
|
||||
|
||||
// setup to read the internal temperature sensor
|
||||
|
||||
// ADC used to sample the temperature sensor
|
||||
adc_config = RFM22_ac_adcsel_temp_sensor | RFM22_ac_adcref_bg;
|
||||
rfm22_write(RFM22_adc_config, adc_config);
|
||||
|
||||
// adc offset
|
||||
rfm22_write(RFM22_adc_sensor_amp_offset, 0);
|
||||
|
||||
// temp sensor calibration .. –40C to +64C 0.5C resolution
|
||||
rfm22_write(RFM22_temp_sensor_calib, RFM22_tsc_tsrange0 | RFM22_tsc_entsoffs);
|
||||
|
||||
// temp sensor offset
|
||||
rfm22_write(RFM22_temp_value_offset, 0);
|
||||
|
||||
// start an ADC conversion
|
||||
rfm22_write(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);
|
||||
|
||||
// enable the internal Tx & Rx packet handlers (without CRC)
|
||||
rfm22_write(RFM22_data_access_control, RFM22_dac_enpacrx | RFM22_dac_enpactx);
|
||||
|
||||
// x-nibbles tx preamble
|
||||
rfm22_write(RFM22_preamble_length, TX_PREAMBLE_NIBBLES);
|
||||
// x-nibbles rx preamble detection
|
||||
rfm22_write(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);
|
||||
|
||||
// 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_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_header_cntl1_bcen_0 |
|
||||
RFM22_header_cntl1_bcen_1 |
|
||||
RFM22_header_cntl1_bcen_2 |
|
||||
RFM22_header_cntl1_bcen_3 |
|
||||
RFM22_header_cntl1_hdch_0 |
|
||||
RFM22_header_cntl1_hdch_1 |
|
||||
RFM22_header_cntl1_hdch_2 |
|
||||
RFM22_header_cntl1_hdch_3);
|
||||
// Check all bit of all bytes of the header
|
||||
rfm22_write(RFM22_header_enable0, 0xff);
|
||||
rfm22_write(RFM22_header_enable1, 0xff);
|
||||
rfm22_write(RFM22_header_enable2, 0xff);
|
||||
rfm22_write(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);
|
||||
// 4 header bytes, synchronization word length 3, 2, 1 & 0 used, packet length included in header.
|
||||
rfm22_write(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(RFM22_agc_override1, RFM22_agc_ovr1_agcen);
|
||||
|
||||
// set frequency hopping channel step size (multiples of 10kHz)
|
||||
rfm22_write(RFM22_frequency_hopping_step_size, frequency_hop_step_size_reg);
|
||||
|
||||
// set our nominal carrier frequency
|
||||
rfm22_setNominalCarrierFrequency((min_frequency_hz + max_frequency_hz) / 2);
|
||||
|
||||
// set the tx power
|
||||
rfm22_write(RFM22_tx_power, RFM22_tx_pwr_papeaken | RFM22_tx_pwr_papeaklvl_0 |
|
||||
RFM22_tx_pwr_lna_sw | tx_power);
|
||||
|
||||
// TX FIFO Almost Full Threshold (0 - 63)
|
||||
rfm22_write(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);
|
||||
|
||||
// RX FIFO Almost Full Threshold (0 - 63)
|
||||
rfm22_write(RFM22_rx_fifo_control, RX_FIFO_HI_WATERMARK);
|
||||
|
||||
// Enable RF module external interrupt
|
||||
rfm22_enableExtInt();
|
||||
|
||||
rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false);
|
||||
|
||||
initialized = true;
|
||||
|
||||
return 0; // ok
|
||||
}
|
||||
|
||||
// ************************************
|
||||
|
||||
#endif
|
||||
|
||||
/**
|
||||
* @}
|
||||
* @}
|
||||
*/
|
@ -3,7 +3,8 @@ PROVIDE ( vPortSVCHandler = 0 ) ;
|
||||
PROVIDE ( xPortPendSVHandler = 0 ) ;
|
||||
PROVIDE ( xPortSysTickHandler = 0 ) ;
|
||||
|
||||
_estack = 0x20004FF0;
|
||||
/* This is the size of the stack for early init and for all FreeRTOS IRQs */
|
||||
_irq_stack_size = 0x400;
|
||||
|
||||
/* Section Definitions */
|
||||
SECTIONS
|
||||
@ -49,6 +50,24 @@ SECTIONS
|
||||
_ebss = . ;
|
||||
} > SRAM
|
||||
|
||||
/*
|
||||
* This stack is used both as the initial sp during early init as well as ultimately
|
||||
* being used as the STM32's MSP (Main Stack Pointer) which is the same stack that
|
||||
* is used for _all_ interrupt handlers. The end of this stack should be placed
|
||||
* against the lowest address in RAM so that a stack overrun results in a hard fault
|
||||
* at the first access beyond the end of the stack.
|
||||
*/
|
||||
.irq_stack :
|
||||
{
|
||||
. = ALIGN(4);
|
||||
_irq_stack_end = . ;
|
||||
. = . + _irq_stack_size ;
|
||||
. = ALIGN(4);
|
||||
_irq_stack_top = . - 4 ;
|
||||
_init_stack_top = _irq_stack_top;
|
||||
. = ALIGN(4);
|
||||
} > SRAM
|
||||
|
||||
. = ALIGN(4);
|
||||
_end = . ;
|
||||
|
||||
@ -56,6 +75,39 @@ SECTIONS
|
||||
{
|
||||
. = ALIGN(4);
|
||||
KEEP(*(.boardinfo))
|
||||
. = ALIGN(4);
|
||||
} > BD_INFO
|
||||
|
||||
/* Stabs debugging sections. */
|
||||
.stab 0 : { *(.stab) }
|
||||
.stabstr 0 : { *(.stabstr) }
|
||||
.stab.excl 0 : { *(.stab.excl) }
|
||||
.stab.exclstr 0 : { *(.stab.exclstr) }
|
||||
.stab.index 0 : { *(.stab.index) }
|
||||
.stab.indexstr 0 : { *(.stab.indexstr) }
|
||||
.comment 0 : { *(.comment) }
|
||||
/* DWARF debug sections.
|
||||
Symbols in the DWARF debugging sections are relative to the beginning
|
||||
of the section so we begin them at 0. */
|
||||
/* DWARF 1 */
|
||||
.debug 0 : { *(.debug) }
|
||||
.line 0 : { *(.line) }
|
||||
/* GNU DWARF 1 extensions */
|
||||
.debug_srcinfo 0 : { *(.debug_srcinfo) }
|
||||
.debug_sfnames 0 : { *(.debug_sfnames) }
|
||||
/* DWARF 1.1 and DWARF 2 */
|
||||
.debug_aranges 0 : { *(.debug_aranges) }
|
||||
.debug_pubnames 0 : { *(.debug_pubnames) }
|
||||
/* DWARF 2 */
|
||||
.debug_info 0 : { *(.debug_info .gnu.linkonce.wi.*) }
|
||||
.debug_abbrev 0 : { *(.debug_abbrev) }
|
||||
.debug_line 0 : { *(.debug_line) }
|
||||
.debug_frame 0 : { *(.debug_frame) }
|
||||
.debug_str 0 : { *(.debug_str) }
|
||||
.debug_loc 0 : { *(.debug_loc) }
|
||||
.debug_macinfo 0 : { *(.debug_macinfo) }
|
||||
/* SGI/MIPS DWARF 2 extensions */
|
||||
.debug_weaknames 0 : { *(.debug_weaknames) }
|
||||
.debug_funcnames 0 : { *(.debug_funcnames) }
|
||||
.debug_typenames 0 : { *(.debug_typenames) }
|
||||
.debug_varnames 0 : { *(.debug_varnames) }
|
||||
}
|
||||
|
@ -1,3 +1,8 @@
|
||||
/* This is the size of the stack for all FreeRTOS IRQs */
|
||||
_irq_stack_size = 0x1A0;
|
||||
/* This is the size of the stack for early init: life span is until scheduler starts */
|
||||
_init_stack_size = 0x100;
|
||||
|
||||
/* Stub out these functions since we don't use them anyway */
|
||||
PROVIDE ( vPortSVCHandler = 0 ) ;
|
||||
PROVIDE ( xPortPendSVHandler = 0 ) ;
|
||||
@ -5,8 +10,6 @@ PROVIDE ( xPortSysTickHandler = 0 ) ;
|
||||
|
||||
PROVIDE(pios_board_info_blob = ORIGIN(BD_INFO));
|
||||
|
||||
_estack = 0x20004FF0;
|
||||
|
||||
/* Section Definitions */
|
||||
SECTIONS
|
||||
{
|
||||
@ -19,6 +22,16 @@ SECTIONS
|
||||
*(.rodata .rodata* .gnu.linkonce.r.*)
|
||||
} > FLASH
|
||||
|
||||
/* module sections */
|
||||
.initcallmodule.init :
|
||||
{
|
||||
. = ALIGN(4);
|
||||
__module_initcall_start = .;
|
||||
KEEP(*(.initcallmodule.init))
|
||||
. = ALIGN(4);
|
||||
__module_initcall_end = .;
|
||||
} >FLASH
|
||||
|
||||
.ARM.extab :
|
||||
{
|
||||
*(.ARM.extab* .gnu.linkonce.armextab.*)
|
||||
@ -33,6 +46,23 @@ SECTIONS
|
||||
_etext = .;
|
||||
_sidata = .;
|
||||
|
||||
/*
|
||||
* This stack is used both as the initial sp during early init as well as ultimately
|
||||
* being used as the STM32's MSP (Main Stack Pointer) which is the same stack that
|
||||
* is used for _all_ interrupt handlers. The end of this stack should be placed
|
||||
* against the lowest address in RAM so that a stack overrun results in a hard fault
|
||||
* at the first access beyond the end of the stack.
|
||||
*/
|
||||
.irq_stack :
|
||||
{
|
||||
. = ALIGN(4);
|
||||
_irq_stack_end = . ;
|
||||
. = . + _irq_stack_size ;
|
||||
. = ALIGN(4);
|
||||
_irq_stack_top = . - 4 ;
|
||||
. = ALIGN(4);
|
||||
} > SRAM
|
||||
|
||||
.data : AT (_etext)
|
||||
{
|
||||
_sdata = .;
|
||||
@ -41,16 +71,81 @@ SECTIONS
|
||||
_edata = . ;
|
||||
} > SRAM
|
||||
|
||||
|
||||
|
||||
/* .bss section which is used for uninitialized data */
|
||||
.bss (NOLOAD) :
|
||||
{
|
||||
_sbss = . ;
|
||||
*(.bss .bss.*)
|
||||
*(COMMON)
|
||||
. = ALIGN(4);
|
||||
_ebss = . ;
|
||||
} > SRAM
|
||||
|
||||
. = ALIGN(4);
|
||||
_end = . ;
|
||||
.heap (NOLOAD) :
|
||||
{
|
||||
. = ALIGN(4);
|
||||
_sheap = . ;
|
||||
_sheap_pre_rtos = . ;
|
||||
*(.heap)
|
||||
. = ALIGN(4);
|
||||
_eheap = . ;
|
||||
_eheap_pre_rtos = . ;
|
||||
_init_stack_end = . ;
|
||||
_sheap_post_rtos = . ;
|
||||
. = . + _init_stack_size ;
|
||||
. = ALIGN(4);
|
||||
_eheap_post_rtos = . ;
|
||||
_init_stack_top = . - 4 ;
|
||||
} > SRAM
|
||||
|
||||
|
||||
_free_ram = . ;
|
||||
.free_ram (NOLOAD) :
|
||||
{
|
||||
. = ORIGIN(SRAM) + LENGTH(SRAM) - _free_ram ;
|
||||
/* This is used by the startup in order to initialize the .bss section */
|
||||
_ebss = . ;
|
||||
_eram = . ;
|
||||
} > SRAM
|
||||
|
||||
/* keep the heap section at the end of the SRAM
|
||||
* this will allow to claim the remaining bytes not used
|
||||
* at run time! (done by the reset vector).
|
||||
*/
|
||||
|
||||
PROVIDE ( _end = _ebss ) ;
|
||||
|
||||
/* Stabs debugging sections. */
|
||||
.stab 0 : { *(.stab) }
|
||||
.stabstr 0 : { *(.stabstr) }
|
||||
.stab.excl 0 : { *(.stab.excl) }
|
||||
.stab.exclstr 0 : { *(.stab.exclstr) }
|
||||
.stab.index 0 : { *(.stab.index) }
|
||||
.stab.indexstr 0 : { *(.stab.indexstr) }
|
||||
.comment 0 : { *(.comment) }
|
||||
/* DWARF debug sections.
|
||||
Symbols in the DWARF debugging sections are relative to the beginning
|
||||
of the section so we begin them at 0. */
|
||||
/* DWARF 1 */
|
||||
.debug 0 : { *(.debug) }
|
||||
.line 0 : { *(.line) }
|
||||
/* GNU DWARF 1 extensions */
|
||||
.debug_srcinfo 0 : { *(.debug_srcinfo) }
|
||||
.debug_sfnames 0 : { *(.debug_sfnames) }
|
||||
/* DWARF 1.1 and DWARF 2 */
|
||||
.debug_aranges 0 : { *(.debug_aranges) }
|
||||
.debug_pubnames 0 : { *(.debug_pubnames) }
|
||||
/* DWARF 2 */
|
||||
.debug_info 0 : { *(.debug_info .gnu.linkonce.wi.*) }
|
||||
.debug_abbrev 0 : { *(.debug_abbrev) }
|
||||
.debug_line 0 : { *(.debug_line) }
|
||||
.debug_frame 0 : { *(.debug_frame) }
|
||||
.debug_str 0 : { *(.debug_str) }
|
||||
.debug_loc 0 : { *(.debug_loc) }
|
||||
.debug_macinfo 0 : { *(.debug_macinfo) }
|
||||
/* SGI/MIPS DWARF 2 extensions */
|
||||
.debug_weaknames 0 : { *(.debug_weaknames) }
|
||||
.debug_funcnames 0 : { *(.debug_funcnames) }
|
||||
.debug_typenames 0 : { *(.debug_typenames) }
|
||||
.debug_varnames 0 : { *(.debug_varnames) }
|
||||
}
|
||||
|
155
flight/PiOS/STM32F10x/pios_eeprom.c
Normal file
155
flight/PiOS/STM32F10x/pios_eeprom.c
Normal file
@ -0,0 +1,155 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup PIOS PIOS Core hardware abstraction layer
|
||||
* @{
|
||||
* @addtogroup PIOS_EEPROM EEPROM reading/writing functions
|
||||
* @brief PIOS EEPROM reading/writing functions
|
||||
* @{
|
||||
*
|
||||
* @file pios_eeprom.c
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @brief COM layer functions
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
*
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* This program is free software; you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation; either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful, but
|
||||
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
|
||||
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
|
||||
* for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License along
|
||||
* with this program; if not, write to the Free Software Foundation, Inc.,
|
||||
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
*/
|
||||
|
||||
/* Project Includes */
|
||||
#include <pios.h>
|
||||
#include <pios_crc.h>
|
||||
#include <stm32f10x_flash.h>
|
||||
#include <pios_board_info.h>
|
||||
|
||||
#include <pios_eeprom.h>
|
||||
|
||||
static struct pios_eeprom_cfg config;
|
||||
|
||||
/**
|
||||
* Initialize the flash eeprom device
|
||||
* \param cfg The configuration structure.
|
||||
*/
|
||||
void PIOS_EEPROM_Init(const struct pios_eeprom_cfg *cfg)
|
||||
{
|
||||
config = *cfg;
|
||||
}
|
||||
|
||||
/**
|
||||
* Save a block of data to the flash eeprom device.
|
||||
* \param data A pointer to the data to write.
|
||||
* \param len The length of data to write.
|
||||
* \return 0 on sucess
|
||||
*/
|
||||
int32_t PIOS_EEPROM_Save(uint8_t *data, uint32_t len)
|
||||
{
|
||||
|
||||
// We need to write 32 bit words, so extend the length to be an even multiple of 4 bytes,
|
||||
// and include 4 bytes for the 32 bit CRC.
|
||||
uint32_t nwords = (len / 4) + 1 + (len % 4 ? 1 : 0);
|
||||
uint32_t size = nwords * 4;
|
||||
|
||||
// Ensure that the length is not longer than the max size.
|
||||
if (size > config.max_size)
|
||||
return -1;
|
||||
|
||||
// Calculate a 32 bit CRC of the data.
|
||||
uint32_t crc = PIOS_CRC32_updateCRC(0xffffffff, data, len);
|
||||
|
||||
// Unlock the Flash Program Erase controller
|
||||
FLASH_Unlock();
|
||||
|
||||
// See if we have to write the data.
|
||||
if ((memcmp(data, (uint8_t*)config.base_address, len) == 0) &&
|
||||
(memcmp((uint8_t*)&crc, (uint8_t*)config.base_address + size - 4, 4) == 0))
|
||||
return 0;
|
||||
|
||||
// TODO: Check that the area isn't already erased
|
||||
|
||||
// Erase page
|
||||
FLASH_Status fs = FLASH_ErasePage(config.base_address);
|
||||
if (fs != FLASH_COMPLETE)
|
||||
{ // error
|
||||
FLASH_Lock();
|
||||
return -2;
|
||||
}
|
||||
|
||||
// write 4 bytes at a time into program flash area (emulated EEPROM area)
|
||||
uint8_t *p1 = data;
|
||||
uint32_t *p3 = (uint32_t *)config.base_address;
|
||||
for (int32_t i = 0; i < size; p3++)
|
||||
{
|
||||
uint32_t value = 0;
|
||||
|
||||
if (i == (size - 4))
|
||||
{
|
||||
// write the CRC.
|
||||
value = crc;
|
||||
i += 4;
|
||||
}
|
||||
else
|
||||
{
|
||||
if (i < len) value |= (uint32_t)*p1++ << 0; else value |= 0x000000ff; i++;
|
||||
if (i < len) value |= (uint32_t)*p1++ << 8; else value |= 0x0000ff00; i++;
|
||||
if (i < len) value |= (uint32_t)*p1++ << 16; else value |= 0x00ff0000; i++;
|
||||
if (i < len) value |= (uint32_t)*p1++ << 24; else value |= 0xff000000; i++;
|
||||
}
|
||||
|
||||
// write a 32-bit value
|
||||
fs = FLASH_ProgramWord((uint32_t)p3, value);
|
||||
if (fs != FLASH_COMPLETE)
|
||||
{
|
||||
FLASH_Lock();
|
||||
return -3;
|
||||
}
|
||||
}
|
||||
|
||||
// Lock the Flash Program Erase controller
|
||||
FLASH_Lock();
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* Reads a block of data from the flash eeprom device.
|
||||
* \param data A pointer to the output data buffer.
|
||||
* \param len The length of data to read.
|
||||
* \return 0 on sucess
|
||||
*/
|
||||
int32_t PIOS_EEPROM_Load(uint8_t *data, uint32_t len)
|
||||
{
|
||||
|
||||
// We need to write 32 bit words, so the length should have been extended
|
||||
// to an even multiple of 4 bytes, and should include 4 bytes for the 32 bit CRC.
|
||||
uint32_t nwords = (len / 4) + 1 + (len % 4 ? 1 : 0);
|
||||
uint32_t size = nwords * 4;
|
||||
|
||||
// Ensure that the length is not longer than the max size.
|
||||
if (size > config.max_size)
|
||||
return -1;
|
||||
|
||||
// Read the data from flash.
|
||||
memcpy(data, (uint8_t*)config.base_address, len);
|
||||
|
||||
// Read the CRC.
|
||||
uint32_t crc_flash = *((uint32_t*)(config.base_address + size - 4));
|
||||
|
||||
// Calculate a 32 bit CRC of the data.
|
||||
uint32_t crc = PIOS_CRC32_updateCRC(0xffffffff, data, len);
|
||||
if(crc != crc_flash)
|
||||
return -2;
|
||||
|
||||
return 0;
|
||||
}
|
427
flight/PiOS/STM32F10x/startup_stm32f10x_MD_PX.S
Normal file
427
flight/PiOS/STM32F10x/startup_stm32f10x_MD_PX.S
Normal file
@ -0,0 +1,427 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @file startup_stm32f10x_md.s
|
||||
* @author MCD Application Team / Angus Peart
|
||||
* @version V3.1.2
|
||||
* @date 09/28/2009
|
||||
* @brief STM32F10x Medium Density Devices vector table for RIDE7 toolchain.
|
||||
* This module performs:
|
||||
* - Set the initial SP
|
||||
* - Set the initial PC == Reset_Handler,
|
||||
* - Set the vector table entries with the exceptions ISR address
|
||||
* - Branches to main in the C library (which eventually
|
||||
* calls main()).
|
||||
* After Reset the Cortex-M3 processor is in Thread mode,
|
||||
* priority is Privileged, and the Stack is set to Main.
|
||||
*******************************************************************************
|
||||
* @copy
|
||||
*
|
||||
* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
|
||||
* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE
|
||||
* TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY
|
||||
* DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING
|
||||
* FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE
|
||||
* CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
|
||||
*
|
||||
* <h2><center>© COPYRIGHT 2009 STMicroelectronics</center></h2>
|
||||
*/
|
||||
|
||||
.syntax unified
|
||||
.cpu cortex-m3
|
||||
.fpu softvfp
|
||||
.thumb
|
||||
|
||||
.global g_pfnVectors
|
||||
.global Default_Handler
|
||||
.global xPortIncreaseHeapSize
|
||||
.global Stack_Change
|
||||
|
||||
/* start address for the initialization values of the .data section.
|
||||
defined in linker script */
|
||||
.word _sidata
|
||||
/* start address for the .data section. defined in linker script */
|
||||
.word _sdata
|
||||
/* end address for the .data section. defined in linker script */
|
||||
.word _edata
|
||||
/* start address for the .bss section. defined in linker script */
|
||||
.word _sbss
|
||||
/* end address for the .bss section. defined in linker script */
|
||||
.word _ebss
|
||||
|
||||
.equ BootRAM, 0xF108F85F
|
||||
/**
|
||||
* @brief This is the code that gets called when the processor first
|
||||
* starts execution following a reset event. Only the absolutely
|
||||
* necessary set is performed, after which the application
|
||||
* supplied main() routine is called.
|
||||
* @param None
|
||||
* @retval : None
|
||||
*/
|
||||
|
||||
.section .text.Reset_Handler
|
||||
.weak Reset_Handler
|
||||
.type Reset_Handler, %function
|
||||
Reset_Handler:
|
||||
|
||||
/*
|
||||
* From COrtex-M3 reference manual:
|
||||
* - Handler IRQ always use SP_main
|
||||
* - Process use SP_main or SP_process
|
||||
* Here, we will use beginning of SRAM for IRQ (SP_main)
|
||||
* and end of heap for initialization (SP_process).
|
||||
* Once the schedule starts, all threads will use their own stack
|
||||
* from heap and NOBOBY should use SP_process again.
|
||||
*/
|
||||
/* Do set/reset the stack pointers */
|
||||
LDR r0, =_irq_stack_top
|
||||
MSR msp, r0
|
||||
LDR r2, =_init_stack_top
|
||||
MSR psp, r2
|
||||
/* check if irq and init stack are the same */
|
||||
/* if they are, we don't do stack swap */
|
||||
/* and lets bypass the monitoring as well for now */
|
||||
cmp r0, r2
|
||||
beq SectionBssInit
|
||||
/* DO
|
||||
* - stay in thread process mode
|
||||
* - stay in privilege level
|
||||
* - use process stack
|
||||
*/
|
||||
movs r0, #2
|
||||
MSR control, r0
|
||||
ISB
|
||||
/* Fill IRQ stack for watermark monitoring */
|
||||
ldr r2, =_irq_stack_end
|
||||
b LoopFillIRQStack
|
||||
|
||||
FillIRQStack:
|
||||
movw r3, #0xA5A5
|
||||
str r3, [r2], #4
|
||||
|
||||
LoopFillIRQStack:
|
||||
ldr r3, = _irq_stack_top
|
||||
cmp r2, r3
|
||||
bcc FillIRQStack
|
||||
|
||||
SectionBssInit:
|
||||
/* Copy the data segment initializers from flash to SRAM */
|
||||
movs r1, #0
|
||||
b LoopCopyDataInit
|
||||
|
||||
CopyDataInit:
|
||||
ldr r3, =_sidata
|
||||
ldr r3, [r3, r1]
|
||||
str r3, [r0, r1]
|
||||
adds r1, r1, #4
|
||||
|
||||
LoopCopyDataInit:
|
||||
ldr r0, =_sdata
|
||||
ldr r3, =_edata
|
||||
adds r2, r0, r1
|
||||
cmp r2, r3
|
||||
bcc CopyDataInit
|
||||
ldr r2, =_sbss
|
||||
b LoopFillZerobss
|
||||
/* Zero fill the bss segment. */
|
||||
FillZerobss:
|
||||
movs r3, #0
|
||||
str r3, [r2], #4
|
||||
|
||||
LoopFillZerobss:
|
||||
ldr r3, = _ebss
|
||||
cmp r2, r3
|
||||
bcc FillZerobss
|
||||
/* Call the application's entry point.*/
|
||||
bl main
|
||||
/* will never return here */
|
||||
bx lr
|
||||
.size Reset_Handler, .-Reset_Handler
|
||||
|
||||
/**
|
||||
* @brief This is the code that swaps stack (from end of heap to irq_stack).
|
||||
* Also reclaim the heap that was used as a stack.
|
||||
* @param None
|
||||
* @retval : None
|
||||
*/
|
||||
.section .text.Stack_Change
|
||||
.weak Stack_Change
|
||||
.type Stack_Change, %function
|
||||
Stack_Change:
|
||||
mov r4, lr
|
||||
/* Switches stack back momentarily to MSP */
|
||||
movs r0, #0
|
||||
msr control, r0
|
||||
Heap_Reclaim:
|
||||
/* add heap_post_rtos to the heap (if the capability/function exist) */
|
||||
/* Also claim the unused memory (between end of heap to end of memory */
|
||||
/* CAREFULL: the heap section must be the last section in RAM in order this to work */
|
||||
ldr r0, = _init_stack_size
|
||||
ldr r1, = _eheap_post_rtos
|
||||
ldr r2, = _eram
|
||||
subs r2, r2, r1
|
||||
adds r0, r0, r2
|
||||
bl xPortIncreaseHeapSize
|
||||
bx r4
|
||||
.size Stack_Change, .-Stack_Change
|
||||
|
||||
|
||||
/**
|
||||
* @brief This is the code that gets called when the processor receives an
|
||||
* unexpected interrupt. This simply enters an infinite loop, preserving
|
||||
* the system state for examination by a debugger.
|
||||
*
|
||||
* @param None
|
||||
* @retval : None
|
||||
*/
|
||||
.section .text.Default_Handler,"ax",%progbits
|
||||
Default_Handler:
|
||||
Infinite_Loop:
|
||||
b Infinite_Loop
|
||||
.size Default_Handler, .-Default_Handler
|
||||
/******************************************************************************
|
||||
*
|
||||
* The minimal vector table for a Cortex M3. Note that the proper constructs
|
||||
* must be placed on this to ensure that it ends up at physical address
|
||||
* 0x0000.0000.
|
||||
*
|
||||
******************************************************************************/
|
||||
.section .isr_vector,"a",%progbits
|
||||
.type g_pfnVectors, %object
|
||||
.size g_pfnVectors, .-g_pfnVectors
|
||||
|
||||
|
||||
g_pfnVectors:
|
||||
.word _irq_stack_top
|
||||
.word Reset_Handler
|
||||
.word NMI_Handler
|
||||
.word HardFault_Handler
|
||||
.word MemManage_Handler
|
||||
.word BusFault_Handler
|
||||
.word UsageFault_Handler
|
||||
.word 0
|
||||
.word 0
|
||||
.word 0
|
||||
.word 0
|
||||
.word vPortSVCHandler
|
||||
.word DebugMon_Handler
|
||||
.word 0
|
||||
.word xPortPendSVHandler
|
||||
.word xPortSysTickHandler
|
||||
.word WWDG_IRQHandler
|
||||
.word PVD_IRQHandler
|
||||
.word TAMPER_IRQHandler
|
||||
.word RTC_IRQHandler
|
||||
.word FLASH_IRQHandler
|
||||
.word RCC_IRQHandler
|
||||
.word EXTI0_IRQHandler
|
||||
.word EXTI1_IRQHandler
|
||||
.word EXTI2_IRQHandler
|
||||
.word EXTI3_IRQHandler
|
||||
.word EXTI4_IRQHandler
|
||||
.word DMA1_Channel1_IRQHandler
|
||||
.word DMA1_Channel2_IRQHandler
|
||||
.word DMA1_Channel3_IRQHandler
|
||||
.word DMA1_Channel4_IRQHandler
|
||||
.word DMA1_Channel5_IRQHandler
|
||||
.word DMA1_Channel6_IRQHandler
|
||||
.word DMA1_Channel7_IRQHandler
|
||||
.word ADC1_2_IRQHandler
|
||||
.word USB_HP_CAN1_TX_IRQHandler
|
||||
.word USB_LP_CAN1_RX0_IRQHandler
|
||||
.word CAN1_RX1_IRQHandler
|
||||
.word CAN1_SCE_IRQHandler
|
||||
.word EXTI9_5_IRQHandler
|
||||
.word TIM1_BRK_IRQHandler
|
||||
.word TIM1_UP_IRQHandler
|
||||
.word TIM1_TRG_COM_IRQHandler
|
||||
.word TIM1_CC_IRQHandler
|
||||
.word TIM2_IRQHandler
|
||||
.word TIM3_IRQHandler
|
||||
.word TIM4_IRQHandler
|
||||
.word I2C1_EV_IRQHandler
|
||||
.word I2C1_ER_IRQHandler
|
||||
.word I2C2_EV_IRQHandler
|
||||
.word I2C2_ER_IRQHandler
|
||||
.word SPI1_IRQHandler
|
||||
.word SPI2_IRQHandler
|
||||
.word USART1_IRQHandler
|
||||
.word USART2_IRQHandler
|
||||
.word USART3_IRQHandler
|
||||
.word EXTI15_10_IRQHandler
|
||||
.word RTCAlarm_IRQHandler
|
||||
.word USBWakeUp_IRQHandler
|
||||
.word 0
|
||||
.word 0
|
||||
.word 0
|
||||
.word 0
|
||||
.word 0
|
||||
.word 0
|
||||
.word 0
|
||||
.word BootRAM /* @0x108. This is for boot in RAM mode for
|
||||
STM32F10x Medium Density devices. */
|
||||
|
||||
/*******************************************************************************
|
||||
*
|
||||
* Provide weak aliases for each Exception handler to the Default_Handler.
|
||||
* As they are weak aliases, any function with the same name will override
|
||||
* this definition.
|
||||
*
|
||||
*******************************************************************************/
|
||||
|
||||
.weak NMI_Handler
|
||||
.thumb_set NMI_Handler,Default_Handler
|
||||
|
||||
.weak HardFault_Handler
|
||||
.thumb_set HardFault_Handler,Default_Handler
|
||||
|
||||
.weak MemManage_Handler
|
||||
.thumb_set MemManage_Handler,Default_Handler
|
||||
|
||||
.weak BusFault_Handler
|
||||
.thumb_set BusFault_Handler,Default_Handler
|
||||
|
||||
.weak UsageFault_Handler
|
||||
.thumb_set UsageFault_Handler,Default_Handler
|
||||
|
||||
.weak SVC_Handler
|
||||
.thumb_set SVC_Handler,Default_Handler
|
||||
|
||||
.weak DebugMon_Handler
|
||||
.thumb_set DebugMon_Handler,Default_Handler
|
||||
|
||||
.weak PendSV_Handler
|
||||
.thumb_set PendSV_Handler,Default_Handler
|
||||
|
||||
.weak SysTick_Handler
|
||||
.thumb_set SysTick_Handler,Default_Handler
|
||||
|
||||
.weak WWDG_IRQHandler
|
||||
.thumb_set WWDG_IRQHandler,Default_Handler
|
||||
|
||||
.weak PVD_IRQHandler
|
||||
.thumb_set PVD_IRQHandler,Default_Handler
|
||||
|
||||
.weak TAMPER_IRQHandler
|
||||
.thumb_set TAMPER_IRQHandler,Default_Handler
|
||||
|
||||
.weak RTC_IRQHandler
|
||||
.thumb_set RTC_IRQHandler,Default_Handler
|
||||
|
||||
.weak FLASH_IRQHandler
|
||||
.thumb_set FLASH_IRQHandler,Default_Handler
|
||||
|
||||
.weak RCC_IRQHandler
|
||||
.thumb_set RCC_IRQHandler,Default_Handler
|
||||
|
||||
.weak EXTI0_IRQHandler
|
||||
.thumb_set EXTI0_IRQHandler,Default_Handler
|
||||
|
||||
.weak EXTI1_IRQHandler
|
||||
.thumb_set EXTI1_IRQHandler,Default_Handler
|
||||
|
||||
.weak EXTI2_IRQHandler
|
||||
.thumb_set EXTI2_IRQHandler,Default_Handler
|
||||
|
||||
.weak EXTI3_IRQHandler
|
||||
.thumb_set EXTI3_IRQHandler,Default_Handler
|
||||
|
||||
.weak EXTI4_IRQHandler
|
||||
.thumb_set EXTI4_IRQHandler,Default_Handler
|
||||
|
||||
.weak DMA1_Channel1_IRQHandler
|
||||
.thumb_set DMA1_Channel1_IRQHandler,Default_Handler
|
||||
|
||||
.weak DMA1_Channel2_IRQHandler
|
||||
.thumb_set DMA1_Channel2_IRQHandler,Default_Handler
|
||||
|
||||
.weak DMA1_Channel3_IRQHandler
|
||||
.thumb_set DMA1_Channel3_IRQHandler,Default_Handler
|
||||
|
||||
.weak DMA1_Channel4_IRQHandler
|
||||
.thumb_set DMA1_Channel4_IRQHandler,Default_Handler
|
||||
|
||||
.weak DMA1_Channel5_IRQHandler
|
||||
.thumb_set DMA1_Channel5_IRQHandler,Default_Handler
|
||||
|
||||
.weak DMA1_Channel6_IRQHandler
|
||||
.thumb_set DMA1_Channel6_IRQHandler,Default_Handler
|
||||
|
||||
.weak DMA1_Channel7_IRQHandler
|
||||
.thumb_set DMA1_Channel7_IRQHandler,Default_Handler
|
||||
|
||||
.weak ADC1_2_IRQHandler
|
||||
.thumb_set ADC1_2_IRQHandler,Default_Handler
|
||||
|
||||
.weak USB_HP_CAN1_TX_IRQHandler
|
||||
.thumb_set USB_HP_CAN1_TX_IRQHandler,Default_Handler
|
||||
|
||||
.weak USB_LP_CAN1_RX0_IRQHandler
|
||||
.thumb_set USB_LP_CAN1_RX0_IRQHandler,Default_Handler
|
||||
|
||||
.weak CAN1_RX1_IRQHandler
|
||||
.thumb_set CAN1_RX1_IRQHandler,Default_Handler
|
||||
|
||||
.weak CAN1_SCE_IRQHandler
|
||||
.thumb_set CAN1_SCE_IRQHandler,Default_Handler
|
||||
|
||||
.weak EXTI9_5_IRQHandler
|
||||
.thumb_set EXTI9_5_IRQHandler,Default_Handler
|
||||
|
||||
.weak TIM1_BRK_IRQHandler
|
||||
.thumb_set TIM1_BRK_IRQHandler,Default_Handler
|
||||
|
||||
.weak TIM1_UP_IRQHandler
|
||||
.thumb_set TIM1_UP_IRQHandler,Default_Handler
|
||||
|
||||
.weak TIM1_TRG_COM_IRQHandler
|
||||
.thumb_set TIM1_TRG_COM_IRQHandler,Default_Handler
|
||||
|
||||
.weak TIM1_CC_IRQHandler
|
||||
.thumb_set TIM1_CC_IRQHandler,Default_Handler
|
||||
|
||||
.weak TIM2_IRQHandler
|
||||
.thumb_set TIM2_IRQHandler,Default_Handler
|
||||
|
||||
.weak TIM3_IRQHandler
|
||||
.thumb_set TIM3_IRQHandler,Default_Handler
|
||||
|
||||
.weak TIM4_IRQHandler
|
||||
.thumb_set TIM4_IRQHandler,Default_Handler
|
||||
|
||||
.weak I2C1_EV_IRQHandler
|
||||
.thumb_set I2C1_EV_IRQHandler,Default_Handler
|
||||
|
||||
.weak I2C1_ER_IRQHandler
|
||||
.thumb_set I2C1_ER_IRQHandler,Default_Handler
|
||||
|
||||
.weak I2C2_EV_IRQHandler
|
||||
.thumb_set I2C2_EV_IRQHandler,Default_Handler
|
||||
|
||||
.weak I2C2_ER_IRQHandler
|
||||
.thumb_set I2C2_ER_IRQHandler,Default_Handler
|
||||
|
||||
.weak SPI1_IRQHandler
|
||||
.thumb_set SPI1_IRQHandler,Default_Handler
|
||||
|
||||
.weak SPI2_IRQHandler
|
||||
.thumb_set SPI2_IRQHandler,Default_Handler
|
||||
|
||||
.weak USART1_IRQHandler
|
||||
.thumb_set USART1_IRQHandler,Default_Handler
|
||||
|
||||
.weak USART2_IRQHandler
|
||||
.thumb_set USART2_IRQHandler,Default_Handler
|
||||
|
||||
.weak USART3_IRQHandler
|
||||
.thumb_set USART3_IRQHandler,Default_Handler
|
||||
|
||||
.weak EXTI15_10_IRQHandler
|
||||
.thumb_set EXTI15_10_IRQHandler,Default_Handler
|
||||
|
||||
.weak RTCAlarm_IRQHandler
|
||||
.thumb_set RTCAlarm_IRQHandler,Default_Handler
|
||||
|
||||
.weak USBWakeUp_IRQHandler
|
||||
.thumb_set USBWakeUp_IRQHandler,Default_Handler
|
||||
|
||||
|
@ -1,3 +1,8 @@
|
||||
#ifndef PIOS_BOARD_INFO_H
|
||||
#define PIOS_BOARD_INFO_H
|
||||
|
||||
#include <stdint.h> /* uint* */
|
||||
|
||||
#define PIOS_BOARD_INFO_BLOB_MAGIC 0xBDBDBDBD
|
||||
|
||||
struct pios_board_info {
|
||||
@ -15,3 +20,5 @@ struct pios_board_info {
|
||||
} __attribute__((packed));
|
||||
|
||||
extern const struct pios_board_info pios_board_info_blob;
|
||||
|
||||
#endif /* PIOS_BOARD_INFO_H */
|
||||
|
@ -29,3 +29,9 @@
|
||||
|
||||
uint8_t PIOS_CRC_updateByte(uint8_t crc, const uint8_t data);
|
||||
uint8_t PIOS_CRC_updateCRC(uint8_t crc, const uint8_t* data, int32_t length);
|
||||
|
||||
uint16_t PIOS_CRC16_updateByte(uint16_t crc, const uint8_t data);
|
||||
uint16_t PIOS_CRC16_updateCRC(uint16_t crc, const uint8_t* data, int32_t length);
|
||||
|
||||
uint32_t PIOS_CRC32_updateByte(uint32_t crc, const uint8_t data);
|
||||
uint32_t PIOS_CRC32_updateCRC(uint32_t crc, const uint8_t* data, int32_t length);
|
||||
|
@ -1,40 +1,50 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup PIOS PIOS Core hardware abstraction layer
|
||||
* @{
|
||||
* @addtogroup PIOS_EEPROM EEPROM reading/writing functions
|
||||
* @brief PIOS EEPROM reading/writing functions
|
||||
* @{
|
||||
*
|
||||
* @file api_config.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @brief RF Module hardware layer
|
||||
* @file pios_eeprom.c
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @brief COM layer functions
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
*
|
||||
*
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* This program is free software; you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation; either version 3 of the License, or
|
||||
/*
|
||||
* 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
|
||||
*
|
||||
* 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.,
|
||||
*
|
||||
* 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 __API_CONFIG_H__
|
||||
#define __API_CONFIG_H__
|
||||
#ifndef PIOS_EEPROM_H
|
||||
#define PIOS_EEPROM_H
|
||||
|
||||
#include "stdint.h"
|
||||
/* Public Structures */
|
||||
struct pios_eeprom_cfg {
|
||||
uint32_t base_address;
|
||||
uint32_t max_size;
|
||||
};
|
||||
|
||||
// *****************************************************************************
|
||||
/* Public Functions */
|
||||
extern void PIOS_EEPROM_Init(const struct pios_eeprom_cfg *cfg);
|
||||
extern int32_t PIOS_EEPROM_Save(uint8_t *data, uint32_t len);
|
||||
extern int32_t PIOS_EEPROM_Load(uint8_t *data, uint32_t len);
|
||||
|
||||
void apiconfig_1ms_tick(void);
|
||||
void apiconfig_process(void);
|
||||
#endif /* PIOS_EEPROM_H */
|
||||
|
||||
void apiconfig_init(void);
|
||||
|
||||
// *****************************************************************************
|
||||
|
||||
#endif
|
||||
/**
|
||||
* @}
|
||||
* @}
|
||||
*/
|
55
flight/PiOS/inc/pios_rfm22b.h
Normal file
55
flight/PiOS/inc/pios_rfm22b.h
Normal file
@ -0,0 +1,55 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup PIOS PIOS Core hardware abstraction layer
|
||||
* @{
|
||||
* @addtogroup PIOS_RFM22B Radio Functions
|
||||
* @brief PIOS interface for RFM22B Radio
|
||||
* @{
|
||||
*
|
||||
* @file pios_rfm22b.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
|
||||
|
||||
/* Global Types */
|
||||
struct pios_rfm22b_cfg {
|
||||
uint32_t frequencyHz;
|
||||
uint32_t minFrequencyHz;
|
||||
uint32_t maxFrequencyHz;
|
||||
uint8_t RFXtalCap;
|
||||
uint32_t maxRFBandwidth;
|
||||
uint8_t maxTxPower;
|
||||
};
|
||||
|
||||
/* Public Functions */
|
||||
extern int32_t PIOS_RFM22B_Init(uint32_t *rfb22b_id, const struct pios_rfm22b_cfg *cfg);
|
||||
extern uint32_t PIOS_RFM22B_DeviceID(uint32_t rfb22b_id);
|
||||
extern int8_t PIOS_RFM22B_RSSI(uint32_t rfm22b_id);
|
||||
extern int16_t PIOS_RFM22B_Resets(uint32_t rfm22b_id);
|
||||
|
||||
#endif /* PIOS_RFM22B_H */
|
||||
|
||||
/**
|
||||
* @}
|
||||
* @}
|
||||
*/
|
@ -1,643 +1,656 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file rfm22b.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @brief RF Module hardware layer
|
||||
* @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 __RFM22B_H__
|
||||
#define __RFM22B_H__
|
||||
|
||||
#include "stdint.h"
|
||||
|
||||
// ************************************
|
||||
|
||||
#define RFM22_DEVICE_VERSION_V2 0x02
|
||||
#define RFM22_DEVICE_VERSION_A0 0x04
|
||||
#define RFM22_DEVICE_VERSION_B1 0x06
|
||||
|
||||
// ************************************
|
||||
|
||||
#define RFM22_MIN_CARRIER_FREQUENCY_HZ 240000000ul
|
||||
#define RFM22_MAX_CARRIER_FREQUENCY_HZ 930000000ul
|
||||
|
||||
// ************************************
|
||||
|
||||
enum { RX_SCAN_SPECTRUM = 0,
|
||||
RX_WAIT_PREAMBLE_MODE,
|
||||
RX_WAIT_SYNC_MODE,
|
||||
RX_DATA_MODE,
|
||||
TX_DATA_MODE,
|
||||
TX_STREAM_MODE,
|
||||
TX_CARRIER_MODE,
|
||||
TX_PN_MODE};
|
||||
|
||||
// ************************************
|
||||
|
||||
#define BIT0 (1u << 0)
|
||||
#define BIT1 (1u << 1)
|
||||
#define BIT2 (1u << 2)
|
||||
#define BIT3 (1u << 3)
|
||||
#define BIT4 (1u << 4)
|
||||
#define BIT5 (1u << 5)
|
||||
#define BIT6 (1u << 6)
|
||||
#define BIT7 (1u << 7)
|
||||
|
||||
// ************************************
|
||||
|
||||
#define RFM22_DEVICE_TYPE 0x00 // R
|
||||
#define RFM22_DT_MASK 0x1F
|
||||
|
||||
#define RFM22_DEVICE_VERSION 0x01 // R
|
||||
#define RFM22_DV_MASK 0x1F
|
||||
|
||||
#define RFM22_device_status 0x02 // R
|
||||
#define RFM22_ds_cps_mask 0x03 // Chip Power State mask
|
||||
#define RFM22_ds_cps_idle 0x00 // IDLE Chip Power State
|
||||
#define RFM22_ds_cps_rx 0x01 // RX Chip Power State
|
||||
#define RFM22_ds_cps_tx 0x02 // TX Chip Power State
|
||||
//#define RFM22_ds_lockdet 0x04 //
|
||||
//#define RFM22_ds_freqerr 0x08 //
|
||||
#define RFM22_ds_headerr 0x10 // Header Error Status. Indicates if the received packet has a header check error
|
||||
#define RFM22_ds_rxffem 0x20 // RX FIFO Empty Status
|
||||
#define RFM22_ds_ffunfl 0x40 // RX/TX FIFO Underflow Status
|
||||
#define RFM22_ds_ffovfl 0x80 // RX/TX FIFO Overflow Status
|
||||
|
||||
#define RFM22_interrupt_status1 0x03 // R
|
||||
#define RFM22_is1_icrerror BIT0 // CRC Error. When set to 1 the cyclic redundancy check is failed.
|
||||
#define RFM22_is1_ipkvalid BIT1 // Valid Packet Received.When set to 1 a valid packet has been received.
|
||||
#define RFM22_is1_ipksent BIT2 // Packet Sent Interrupt. When set to1 a valid packet has been transmitted.
|
||||
#define RFM22_is1_iext BIT3 // External Interrupt. When set to 1 an interrupt occurred on one of the GPIO’s if it is programmed so. The status can be checked in register 0Eh. See GPIOx Configuration section for the details.
|
||||
#define RFM22_is1_irxffafull BIT4 // RX FIFO Almost Full.When set to 1 the RX FIFO has met its almost full threshold and needs to be read by the microcontroller.
|
||||
#define RFM22_is1_ixtffaem BIT5 // TX FIFO Almost Empty. When set to 1 the TX FIFO is almost empty and needs to be filled.
|
||||
#define RFM22_is1_itxffafull BIT6 // TX FIFO Almost Full. When set to 1 the TX FIFO has met its almost full threshold and needs to be transmitted.
|
||||
#define RFM22_is1_ifferr BIT7 // FIFO Underflow/Overflow Error. When set to 1 the TX or RX FIFO has overflowed or underflowed.
|
||||
|
||||
#define RFM22_interrupt_status2 0x04 // R
|
||||
#define RFM22_is2_ipor BIT0 // Power-on-Reset (POR). When the chip detects a Power on Reset above the desired setting this bit will be set to 1.
|
||||
#define RFM22_is2_ichiprdy BIT1 // Chip Ready (XTAL). When a chip ready event has been detected this bit will be set to 1.
|
||||
#define RFM22_is2_ilbd BIT2 // Low Battery Detect. When a low battery event is been detected this bit will be set to 1. This interrupt event is saved even if it is not enabled by the mask register bit and causes an interrupt after it is enabled.
|
||||
#define RFM22_is2_iwut BIT3 // Wake-Up-Timer. On the expiration of programmed wake-up timer this bit will be set to 1.
|
||||
#define RFM22_is2_irssi BIT4 // RSSI. When RSSI level exceeds the programmed threshold this bit will be set to 1.
|
||||
#define RFM22_is2_ipreainval BIT5 // Invalid Preamble Detected. When the preamble is not found within a period of time set by the invalid preamble detection threshold in Register 54h, this bit will be set to 1.
|
||||
#define RFM22_is2_ipreaval BIT6 // Valid Preamble Detected. When a preamble is detected this bit will be set to 1.
|
||||
#define RFM22_is2_iswdet BIT7 // Sync Word Detected. When a sync word is detected this bit will be set to 1.
|
||||
|
||||
#define RFM22_interrupt_enable1 0x05 // R/W
|
||||
#define RFM22_ie1_encrcerror BIT0 // Enable CRC Error. When set to 1 the CRC Error interrupt will be enabled.
|
||||
#define RFM22_ie1_enpkvalid BIT1 // Enable Valid Packet Received. When ipkvalid = 1 the Valid Packet Received Interrupt will be enabled.
|
||||
#define RFM22_ie1_enpksent BIT2 // Enable Packet Sent. When ipksent =1 the Packet Sense Interrupt will be enabled.
|
||||
#define RFM22_ie1_enext BIT3 // Enable External Interrupt. When set to 1 the External Interrupt will be enabled.
|
||||
#define RFM22_ie1_enrxffafull BIT4 // Enable RX FIFO Almost Full. When set to 1 the RX FIFO Almost Full interrupt will be enabled.
|
||||
#define RFM22_ie1_entxffaem BIT5 // Enable TX FIFO Almost Empty. When set to 1 the TX FIFO Almost Empty interrupt will be enabled.
|
||||
#define RFM22_ie1_entxffafull BIT6 // Enable TX FIFO Almost Full. When set to 1 the TX FIFO Almost Full interrupt will be enabled.
|
||||
#define RFM22_ie1_enfferr BIT7 // Enable FIFO Underflow/Overflow. When set to 1 the FIFO Underflow/Overflow interrupt will be enabled.
|
||||
|
||||
#define RFM22_interrupt_enable2 0x06 // R/W
|
||||
#define RFM22_ie2_enpor BIT0 // Enable POR. When set to 1 the POR interrupt will be enabled.
|
||||
#define RFM22_ie2_enchiprdy BIT1 // Enable Chip Ready (XTAL). When set to 1 the Chip Ready interrupt will be enabled.
|
||||
#define RFM22_ie2_enlbd BIT2 // Enable Low Battery Detect. When set to 1 the Low Battery Detect interrupt will be enabled.
|
||||
#define RFM22_ie2_enwut BIT3 // Enable Wake-Up Timer. When set to 1 the Wake-Up Timer interrupt will be enabled.
|
||||
#define RFM22_ie2_enrssi BIT4 // Enable RSSI. When set to 1 the RSSI Interrupt will be enabled.
|
||||
#define RFM22_ie2_enpreainval BIT5 // Enable Invalid Preamble Detected. When mpreadet =1 the Invalid Preamble Detected Interrupt will be enabled.
|
||||
#define RFM22_ie2_enpreaval BIT6 // Enable Valid Preamble Detected. When mpreadet =1 the Valid Preamble Detected Interrupt will be enabled.
|
||||
#define RFM22_ie2_enswdet BIT7 // Enable Sync Word Detected. When mpreadet =1 the Preamble Detected Interrupt will be enabled.
|
||||
|
||||
#define RFM22_op_and_func_ctrl1 0x07 // R/W
|
||||
#define RFM22_opfc1_xton 0x01 // READY Mode (Xtal is ON).
|
||||
#define RFM22_opfc1_pllon 0x02 // TUNE Mode (PLL is ON). When pllon = 1 the PLL will remain enabled in Idle State. This will for faster turn-around time at the cost of increased current consumption in Idle State.
|
||||
#define RFM22_opfc1_rxon 0x04 // RX on in Manual Receiver Mode. Automatically cleared if Multiple Packets config. is disabled and a valid packet received.
|
||||
#define RFM22_opfc1_txon 0x08 // TX on in Manual Transmit Mode. Automatically cleared in FIFO mode once the packet is sent. Transmission can be aborted during packet transmission, however, when no data has been sent yet, transmission can only be aborted after the device is programmed to “unmodulated carrier” ("Register 71h. Modulation Mode Control 2").
|
||||
#define RFM22_opfc1_x32ksel 0x10 // 32,768 kHz Crystal Oscillator Select. 0: RC oscillator 1: 32 kHz crystal
|
||||
#define RFM22_opfc1_enwt 0x20 // Enable Wake-Up-Timer. Enabled when enwt = 1. If the Wake-up-Timer function is enabled it will operate in any mode and notify the microcontroller through the GPIO interrupt when the timer expires.
|
||||
#define RFM22_opfc1_enlbd 0x40 // Enable Low Battery Detect. When this bit is set to 1 the Low Battery Detector circuit and threshold comparison will be enabled.
|
||||
#define RFM22_opfc1_swres 0x80 // Software Register Reset Bit. This bit may be used to reset all registers simultaneously to a DEFAULT state, without the need for sequentially writing to each individual register. The RESET is accomplished by setting swres = 1. This bit will be automatically cleared.
|
||||
|
||||
#define RFM22_op_and_func_ctrl2 0x08 // R/W
|
||||
#define RFM22_opfc2_ffclrtx 0x01 // TX FIFO Reset/Clear. This has to be a two writes operation: Setting ffclrtx =1 followed by ffclrtx = 0 will clear the contents of the TX FIFO.
|
||||
#define RFM22_opfc2_ffclrrx 0x02 // RX FIFO Reset/Clear. This has to be a two writes operation: Setting ffclrrx =1 followed by ffclrrx = 0 will clear the contents of the RX FIFO.
|
||||
#define RFM22_opfc2_enldm 0x04 // Enable Low Duty Cycle Mode. If this bit is set to 1 then the chip turns on the RX regularly. The frequency should be set in the Wake-Up Timer Period register, while the minimum ON time should be set in the Low-Duty Cycle Mode Duration register. The FIFO mode should be enabled also.
|
||||
#define RFM22_opfc2_autotx 0x08 // Automatic Transmission. When autotx = 1 the transceiver will enter automatically TX State when the FIFO is almost full. When the FIFO is empty it will automatically return to the Idle State.
|
||||
#define RFM22_opfc2_rxmpk 0x10 // RX Multi Packet. When the chip is selected to use FIFO Mode (dtmod[1:0]) and RX Packet Handling (enpacrx) then it will fill up the FIFO with multiple valid packets if this bit is set, otherwise the transceiver will automatically leave the RX State after the first valid packet has been received.
|
||||
#define RFM22_opfc2_antdiv_mask 0xE0 // Enable Antenna Diversity. The GPIO must be configured for Antenna Diversity for the algorithm to work properly.
|
||||
|
||||
#define RFM22_xtal_osc_load_cap 0x09 // R/W
|
||||
#define RFM22_xolc_xlc_mask 0x7F // Tuning Capacitance for the 30 MHz XTAL.
|
||||
#define RFM22_xolc_xtalshft 0x80 // Additional capacitance to course shift the frequency if xlc[6:0] is not sufficient. Not binary with xlc[6:0].
|
||||
|
||||
#define RFM22_cpu_output_clk 0x0A // R/W
|
||||
#define RFM22_coc_30MHz 0x00
|
||||
#define RFM22_coc_15MHz 0x01
|
||||
#define RFM22_coc_10MHz 0x02
|
||||
#define RFM22_coc_4MHz 0x03
|
||||
#define RFM22_coc_3MHz 0x04
|
||||
#define RFM22_coc_2MHz 0x05
|
||||
#define RFM22_coc_1MHz 0x06
|
||||
#define RFM22_coc_32768Hz 0x07
|
||||
#define RFM22_coc_enlfc 0x08
|
||||
#define RFM22_coc_0cycle 0x00
|
||||
#define RFM22_coc_128cycles 0x10
|
||||
#define RFM22_coc_256cycles 0x20
|
||||
#define RFM22_coc_512cycles 0x30
|
||||
|
||||
#define RFM22_gpio0_config 0x0B // R/W
|
||||
#define RFM22_gpio0_config_por 0x00 // Power-On-Reset (output)
|
||||
#define RFM22_gpio0_config_wut 0x01 // Wake-Up Timer: 1 when WUT has expired (output)
|
||||
#define RFM22_gpio0_config_lbd 0x02 // Low Battery Detect: 1 when battery is below threshold setting (output)
|
||||
#define RFM22_gpio0_config_ddi 0x03 // Direct Digital Input
|
||||
#define RFM22_gpio0_config_eife 0x04 // External Interrupt, falling edge (input)
|
||||
#define RFM22_gpio0_config_eire 0x05 // External Interrupt, rising edge (input)
|
||||
#define RFM22_gpio0_config_eisc 0x06 // External Interrupt, state change (input)
|
||||
#define RFM22_gpio0_config_ai 0x07 // ADC Analog Input
|
||||
#define RFM22_gpio0_config_atni 0x08 // Reserved (Analog Test N Input)
|
||||
#define RFM22_gpio0_config_atpi 0x09 // Reserved (Analog Test P Input)
|
||||
#define RFM22_gpio0_config_ddo 0x0A // Direct Digital Output
|
||||
#define RFM22_gpio0_config_dto 0x0B // Reserved (Digital Test Output)
|
||||
#define RFM22_gpio0_config_atno 0x0C // Reserved (Analog Test N Output)
|
||||
#define RFM22_gpio0_config_atpo 0x0D // Reserved (Analog Test P Output)
|
||||
#define RFM22_gpio0_config_rv 0xOE // Reference Voltage (output)
|
||||
#define RFM22_gpio0_config_dclk 0x0F // TX/RX Data CLK output to be used in conjunction with TX/RX Data pin (output)
|
||||
#define RFM22_gpio0_config_txd 0x10 // TX Data input for direct modulation (input)
|
||||
#define RFM22_gpio0_config_err 0x11 // External Retransmission Request (input)
|
||||
#define RFM22_gpio0_config_txstate 0x12 // TX State (output)
|
||||
#define RFM22_gpio0_config_txfifoaf 0x13 // TX FIFO Almost Full (output)
|
||||
#define RFM22_gpio0_config_rxd 0x14 // RX Data (output)
|
||||
#define RFM22_gpio0_config_rxstate 0x15 // RX State (output)
|
||||
#define RFM22_gpio0_config_rxfifoaf 0x16 // RX FIFO Almost Full (output)
|
||||
#define RFM22_gpio0_config_antswt1 0x17 // Antenna 1 Switch used for antenna diversity (output)
|
||||
#define RFM22_gpio0_config_antswt2 0x18 // Antenna 2 Switch used for antenna diversity (output)
|
||||
#define RFM22_gpio0_config_vpd 0x19 // Valid Preamble Detected (output)
|
||||
#define RFM22_gpio0_config_ipd 0x1A // Invalid Preamble Detected (output)
|
||||
#define RFM22_gpio0_config_swd 0x1B // Sync Word Detected (output)
|
||||
#define RFM22_gpio0_config_cca 0x1C // Clear Channel Assessment (output)
|
||||
#define RFM22_gpio0_config_vdd 0x1D // VDD
|
||||
#define RFM22_gpio0_config_pup 0x20
|
||||
#define RFM22_gpio0_config_drv0 0x00 // output drive level
|
||||
#define RFM22_gpio0_config_drv1 0x40 // output drive level
|
||||
#define RFM22_gpio0_config_drv2 0x80 // output drive level
|
||||
#define RFM22_gpio0_config_drv3 0xC0 // output drive level
|
||||
|
||||
#define RFM22_gpio1_config 0x0C // R/W
|
||||
#define RFM22_gpio1_config_ipor 0x00 // Inverted Power-On-Reset (output)
|
||||
#define RFM22_gpio1_config_wut 0x01 // Wake-Up Timer: 1 when WUT has expired (output)
|
||||
#define RFM22_gpio1_config_lbd 0x02 // Low Battery Detect: 1 when battery is below threshold setting (output)
|
||||
#define RFM22_gpio1_config_ddi 0x03 // Direct Digital Input
|
||||
#define RFM22_gpio1_config_eife 0x04 // External Interrupt, falling edge (input)
|
||||
#define RFM22_gpio1_config_eire 0x05 // External Interrupt, rising edge (input)
|
||||
#define RFM22_gpio1_config_eisc 0x06 // External Interrupt, state change (input)
|
||||
#define RFM22_gpio1_config_ai 0x07 // ADC Analog Input
|
||||
#define RFM22_gpio1_config_atni 0x08 // Reserved (Analog Test N Input)
|
||||
#define RFM22_gpio1_config_atpi 0x09 // Reserved (Analog Test P Input)
|
||||
#define RFM22_gpio1_config_ddo 0x0A // Direct Digital Output
|
||||
#define RFM22_gpio1_config_dto 0x0B // Reserved (Digital Test Output)
|
||||
#define RFM22_gpio1_config_atno 0x0C // Reserved (Analog Test N Output)
|
||||
#define RFM22_gpio1_config_atpo 0x0D // Reserved (Analog Test P Output)
|
||||
#define RFM22_gpio1_config_rv 0xOE // Reference Voltage (output)
|
||||
#define RFM22_gpio1_config_dclk 0x0F // TX/RX Data CLK output to be used in conjunction with TX/RX Data pin (output)
|
||||
#define RFM22_gpio1_config_txd 0x10 // TX Data input for direct modulation (input)
|
||||
#define RFM22_gpio1_config_err 0x11 // External Retransmission Request (input)
|
||||
#define RFM22_gpio1_config_txstate 0x12 // TX State (output)
|
||||
#define RFM22_gpio1_config_txfifoaf 0x13 // TX FIFO Almost Full (output)
|
||||
#define RFM22_gpio1_config_rxd 0x14 // RX Data (output)
|
||||
#define RFM22_gpio1_config_rxstate 0x15 // RX State (output)
|
||||
#define RFM22_gpio1_config_rxfifoaf 0x16 // RX FIFO Almost Full (output)
|
||||
#define RFM22_gpio1_config_antswt1 0x17 // Antenna 1 Switch used for antenna diversity (output)
|
||||
#define RFM22_gpio1_config_antswt2 0x18 // Antenna 2 Switch used for antenna diversity (output)
|
||||
#define RFM22_gpio1_config_vpd 0x19 // Valid Preamble Detected (output)
|
||||
#define RFM22_gpio1_config_ipd 0x1A // Invalid Preamble Detected (output)
|
||||
#define RFM22_gpio1_config_swd 0x1B // Sync Word Detected (output)
|
||||
#define RFM22_gpio1_config_cca 0x1C // Clear Channel Assessment (output)
|
||||
#define RFM22_gpio1_config_vdd 0x1D // VDD
|
||||
#define RFM22_gpio1_config_pup 0x20
|
||||
#define RFM22_gpio1_config_drv0 0x00 // output drive level
|
||||
#define RFM22_gpio1_config_drv1 0x40 // output drive level
|
||||
#define RFM22_gpio1_config_drv2 0x80 // output drive level
|
||||
#define RFM22_gpio1_config_drv3 0xC0 // output drive level
|
||||
|
||||
#define RFM22_gpio2_config 0x0D // R/W
|
||||
#define RFM22_gpio2_config_mc 0x00 // Microcontroller Clock (output)
|
||||
#define RFM22_gpio2_config_wut 0x01 // Wake-Up Timer: 1 when WUT has expired (output)
|
||||
#define RFM22_gpio2_config_lbd 0x02 // Low Battery Detect: 1 when battery is below threshold setting (output)
|
||||
#define RFM22_gpio2_config_ddi 0x03 // Direct Digital Input
|
||||
#define RFM22_gpio2_config_eife 0x04 // External Interrupt, falling edge (input)
|
||||
#define RFM22_gpio2_config_eire 0x05 // External Interrupt, rising edge (input)
|
||||
#define RFM22_gpio2_config_eisc 0x06 // External Interrupt, state change (input)
|
||||
#define RFM22_gpio2_config_ai 0x07 // ADC Analog Input
|
||||
#define RFM22_gpio2_config_atni 0x08 // Reserved (Analog Test N Input)
|
||||
#define RFM22_gpio2_config_atpi 0x09 // Reserved (Analog Test P Input)
|
||||
#define RFM22_gpio2_config_ddo 0x0A // Direct Digital Output
|
||||
#define RFM22_gpio2_config_dto 0x0B // Reserved (Digital Test Output)
|
||||
#define RFM22_gpio2_config_atno 0x0C // Reserved (Analog Test N Output)
|
||||
#define RFM22_gpio2_config_atpo 0x0D // Reserved (Analog Test P Output)
|
||||
#define RFM22_gpio2_config_rv 0xOE // Reference Voltage (output)
|
||||
#define RFM22_gpio2_config_dclk 0x0F // TX/RX Data CLK output to be used in conjunction with TX/RX Data pin (output)
|
||||
#define RFM22_gpio2_config_txd 0x10 // TX Data input for direct modulation (input)
|
||||
#define RFM22_gpio2_config_err 0x11 // External Retransmission Request (input)
|
||||
#define RFM22_gpio2_config_txstate 0x12 // TX State (output)
|
||||
#define RFM22_gpio2_config_txfifoaf 0x13 // TX FIFO Almost Full (output)
|
||||
#define RFM22_gpio2_config_rxd 0x14 // RX Data (output)
|
||||
#define RFM22_gpio2_config_rxstate 0x15 // RX State (output)
|
||||
#define RFM22_gpio2_config_rxfifoaf 0x16 // RX FIFO Almost Full (output)
|
||||
#define RFM22_gpio2_config_antswt1 0x17 // Antenna 1 Switch used for antenna diversity (output)
|
||||
#define RFM22_gpio2_config_antswt2 0x18 // Antenna 2 Switch used for antenna diversity (output)
|
||||
#define RFM22_gpio2_config_vpd 0x19 // Valid Preamble Detected (output)
|
||||
#define RFM22_gpio2_config_ipd 0x1A // Invalid Preamble Detected (output)
|
||||
#define RFM22_gpio2_config_swd 0x1B // Sync Word Detected (output)
|
||||
#define RFM22_gpio2_config_cca 0x1C // Clear Channel Assessment (output)
|
||||
#define RFM22_gpio2_config_vdd 0x1D // VDD
|
||||
#define RFM22_gpio2_config_pup 0x20
|
||||
#define RFM22_gpio2_config_drv0 0x00 // output drive level
|
||||
#define RFM22_gpio2_config_drv1 0x40 // output drive level
|
||||
#define RFM22_gpio2_config_drv2 0x80 // output drive level
|
||||
#define RFM22_gpio2_config_drv3 0xC0 // output drive level
|
||||
|
||||
#define RFM22_io_port_config 0x0E // R/W
|
||||
#define RFM22_io_port_extitst2 0x40 // External Interrupt Status. If the GPIO2 is programmed to be external interrupt sources then the status can be read here.
|
||||
#define RFM22_io_port_extitst1 0x20 // External Interrupt Status. If the GPIO1 is programmed to be external interrupt sources then the status can be read here.
|
||||
#define RFM22_io_port_extitst0 0x10 // External Interrupt Status. If the GPIO0 is programmed to be external interrupt sources then the status can be read here.
|
||||
#define RFM22_io_port_itsdo 0x08 // Interrupt Request Output on the SDO Pin. nIRQ output is present on the SDO pin if this bit is set and the nSEL input is inactive (high).
|
||||
#define RFM22_io_port_dio2 0x04 // Direct I/O for GPIO2. If the GPIO2 is configured to be a direct output then the value on the GPIO pin can be set here. If the GPIO2 is configured to be a direct input then the value of the pin can be read here.
|
||||
#define RFM22_io_port_dio1 0x02 // Direct I/O for GPIO1. If the GPIO1 is configured to be a direct output then the value on the GPIO pin can be set here. If the GPIO1 is configured to be a direct input then the value of the pin can be read here.
|
||||
#define RFM22_io_port_dio0 0x01 // Direct I/O for GPIO0. If the GPIO0 is configured to be a direct output then the value on the GPIO pin can be set here. If the GPIO0 is configured to be a direct input then the value of the pin can be read here.
|
||||
#define RFM22_io_port_default 0x00 // GPIO pins are default
|
||||
|
||||
#define RFM22_adc_config 0x0F // R/W
|
||||
#define RFM22_ac_adcgain0 0x00
|
||||
#define RFM22_ac_adcgain1 0x01
|
||||
#define RFM22_ac_adcgain2 0x02
|
||||
#define RFM22_ac_adcgain3 0x03
|
||||
#define RFM22_ac_adcref_bg 0x00
|
||||
#define RFM22_ac_adcref_vdd3 0x08
|
||||
#define RFM22_ac_adcref_vdd2 0x0C
|
||||
#define RFM22_ac_adcsel_temp_sensor 0x00
|
||||
#define RFM22_ac_adcsel_gpio0 0x10
|
||||
#define RFM22_ac_adcsel_gpio1 0x20
|
||||
#define RFM22_ac_adcsel_gpio2 0x30
|
||||
#define RFM22_ac_adcsel_gpio01 0x40
|
||||
#define RFM22_ac_adcsel_gpio12 0x50
|
||||
#define RFM22_ac_adcsel_gpio02 0x60
|
||||
#define RFM22_ac_adcsel_gpio_gnd 0x70
|
||||
#define RFM22_ac_adcstartbusy 0x80
|
||||
|
||||
#define RFM22_adc_sensor_amp_offset 0x10 // R/W
|
||||
#define RFM22_asao_adcoffs_mask 0x0F // ADC Sensor Amplifier Offset. The offset can be calculated as Offset = adcoffs[2:0] x VDD/1000; MSB = adcoffs[3] = Sign bit.
|
||||
|
||||
#define RFM22_adc_value 0x11 // R .. Internal 8 bit ADC Output Value.
|
||||
|
||||
#define RFM22_temp_sensor_calib 0x12 // R/W
|
||||
#define RFM22_tsc_tstrim_mask 0x0F // Temperature Sensor Trim Value.
|
||||
#define RFM22_tsc_entstrim 0x10 // Temperature Sensor Trim Enable.
|
||||
#define RFM22_tsc_entsoffs 0x20 // Temperature Sensor Offset to Convert from K to ºC.
|
||||
#define RFM22_tsc_tsrange0 0x00 // Temperature Sensor Range Selection. –64C to +64C 0.5C resolution
|
||||
#define RFM22_tsc_tsrange1 0x40 // -40 to +85C with 1.0C resolution
|
||||
#define RFM22_tsc_tsrange2 0x80 // 0C to 85C with 0.5C resolution
|
||||
#define RFM22_tsc_tsrange3 0xC0 // -40F to 216F with 1.0F resolution
|
||||
|
||||
#define RFM22_temp_value_offset 0x13 // R/W
|
||||
|
||||
#define RFM22_wakeup_timer_period1 0x14 // R/W
|
||||
#define RFM22_wakeup_timer_period2 0x15 // R/W
|
||||
#define RFM22_wakeup_timer_period3 0x16 // R/W
|
||||
|
||||
#define RFM22_wakeup_timer_value1 0x17 // R
|
||||
#define RFM22_wakeup_timer_value2 0x18 // R
|
||||
|
||||
#define RFM22_low_dutycycle_mode_duration 0x19 // R/W
|
||||
#define RFM22_low_battery_detector_threshold 0x1A // R/W
|
||||
|
||||
#define RFM22_battery_volateg_level 0x1B // R
|
||||
|
||||
#define RFM22_if_filter_bandwidth 0x1C // R/W
|
||||
#define RFM22_iffbw_filset_mask 0x0F
|
||||
#define RFM22_iffbw_ndec_exp_mask 0x70
|
||||
#define RFM22_iffbw_dwn3_bypass 0x80
|
||||
|
||||
#define RFM22_afc_loop_gearshift_override 0x1D // R/W
|
||||
#define RFM22_afc_lp_gs_ovrd_afcgearl_mask 0x07 // AFC Low Gear Setting.
|
||||
#define RFM22_afc_lp_gs_ovrd_afcgearh_mask 0x38 // AFC High Gear Setting.
|
||||
#define RFM22_afc_lp_gs_ovrd_enafc 0x40 // AFC Enable.
|
||||
#define RFM22_afc_lp_gs_ovrd_afcbd 0x80 // If set, the tolerated AFC frequency error will be halved.
|
||||
|
||||
#define RFM22_afc_timing_control 0x1E // R/W
|
||||
|
||||
#define RFM22_clk_recovery_gearshift_override 0x1F // R/W
|
||||
#define RFM22_clk_recovery_oversampling_ratio 0x20 // R/W
|
||||
#define RFM22_clk_recovery_offset2 0x21 // R/W
|
||||
#define RFM22_clk_recovery_offset1 0x22 // R/W
|
||||
#define RFM22_clk_recovery_offset0 0x23 // R/W
|
||||
#define RFM22_clk_recovery_timing_loop_gain1 0x24 // R/W
|
||||
#define RFM22_clk_recovery_timing_loop_gain0 0x25 // R/W
|
||||
|
||||
#define RFM22_rssi 0x26 // R
|
||||
#define RFM22_rssi_threshold_clear_chan_indicator 0x27 // R/W
|
||||
|
||||
#define RFM22_antenna_diversity_register1 0x28 // R
|
||||
#define RFM22_antenna_diversity_register2 0x29 // R
|
||||
|
||||
#define RFM22_afc_limiter 0x2A // R/W .. AFC_pull_in_range = ±AFCLimiter[7:0] x (hbsel+1) x 625 Hz
|
||||
|
||||
#define RFM22_afc_correction_read 0x2B // R
|
||||
|
||||
#define RFM22_ook_counter_value1 0x2C // R/W
|
||||
#define RFM22_ook_counter_value2 0x2D // R/W
|
||||
|
||||
#define RFM22_slicer_peak_hold 0x2E // R/W
|
||||
|
||||
#define RFM22_data_access_control 0x30 // R/W
|
||||
#define RFM22_dac_crc_ccitt 0x00 //
|
||||
#define RFM22_dac_crc_crc16 0x01 //
|
||||
#define RFM22_dac_crc_iec16 0x02 //
|
||||
#define RFM22_dac_crc_biacheva 0x03 //
|
||||
#define RFM22_dac_encrc 0x04 // CRC Enable. Cyclic Redundancy Check generation is enabled if this bit is set.
|
||||
#define RFM22_dac_enpactx 0x08 // Enable Packet TX Handling. If FIFO Mode (dtmod = 10) is being used automatic packet handling may be enabled. Setting enpactx = 1 will enable automatic packet handling in the TX path. Register 30–4D allow for various configurations of the packet structure. Setting enpactx = 0 will not do any packet handling in the TX path. It will only transmit what is loaded to the FIFO.
|
||||
#define RFM22_dac_skip2ph 0x10 // Skip 2nd Phase of Preamble Detection. If set, we skip the second phase of the preamble detection (under certain conditions) if antenna diversity is enabled.
|
||||
#define RFM22_dac_crcdonly 0x20 // CRC Data Only Enable. When this bit is set to 1 the CRC is calculated on and checked against the packet data fields only.
|
||||
#define RFM22_dac_lsbfrst 0x40 // LSB First Enable. The LSB of the data will be transmitted/received first if this bit is set.
|
||||
#define RFM22_dac_enpacrx 0x80 // Enable Packet RX Handling. If FIFO Mode (dtmod = 10) is being used automatic packet handling may be enabled. Setting enpacrx = 1 will enable automatic packet handling in the RX path. Register 30–4D allow for various configurations of the packet structure. Setting enpacrx = 0 will not do any packet handling in the RX path. It will only receive everything after the sync word and fill up the RX FIFO.
|
||||
|
||||
#define RFM22_ezmac_status 0x31 // R
|
||||
#define RFM22_ezmac_status_pksent 0x01 // Packet Sent. A 1 a packet has been sent by the radio. (Same bit as in register 03, but reading it does not reset the IRQ)
|
||||
#define RFM22_ezmac_status_pktx 0x02 // Packet Transmitting. When 1 the radio is currently transmitting a packet.
|
||||
#define RFM22_ezmac_status_crcerror 0x04 // CRC Error. When 1 a Cyclic Redundancy Check error has been detected. (Same bit as in register 03, but reading it does not reset the IRQ)
|
||||
#define RFM22_ezmac_status_pkvalid 0x08 // Valid Packet Received. When a 1 a valid packet has been received by the receiver. (Same bit as in register 03, but reading it does not reset the IRQ)
|
||||
#define RFM22_ezmac_status_pkrx 0x10 // Packet Receiving. When 1 the radio is currently receiving a valid packet.
|
||||
#define RFM22_ezmac_status_pksrch 0x20 // Packet Searching. When 1 the radio is searching for a valid packet.
|
||||
#define RFM22_ezmac_status_rxcrc1 0x40 // If high, it indicates the last CRC received is all one’s. May indicated Transmitter underflow in case of CRC error.
|
||||
|
||||
#define RFM22_header_control1 0x32 // R/W
|
||||
#define RFM22_header_cntl1_bcen_none 0x00 // No broadcast address enable.
|
||||
#define RFM22_header_cntl1_bcen_0 0x10 // Broadcast address enable for header byte 0.
|
||||
#define RFM22_header_cntl1_bcen_1 0x20 // Broadcast address enable for header byte 1.
|
||||
#define RFM22_header_cntl1_bcen_01 0x30 // Broadcast address enable for header bytes 0 & 1.
|
||||
#define RFM22_header_cntl1_hdch_none 0x00 // No Received Header check
|
||||
#define RFM22_header_cntl1_hdch_0 0x01 // Received Header check for byte 0.
|
||||
#define RFM22_header_cntl1_hdch_1 0x02 // Received Header check for byte 1.
|
||||
#define RFM22_header_cntl1_hdch_01 0x03 // Received Header check for bytes 0 & 1.
|
||||
|
||||
#define RFM22_header_control2 0x33 // R/W
|
||||
#define RFM22_header_cntl2_prealen 0x01 // MSB of Preamble Length. See register Preamble Length.
|
||||
#define RFM22_header_cntl2_synclen_3 0x00 // Synchronization Word 3
|
||||
#define RFM22_header_cntl2_synclen_32 0x02 // Synchronization Word 3 followed by 2
|
||||
#define RFM22_header_cntl2_synclen_321 0x04 // Synchronization Word 3 followed by 2 followed by 1
|
||||
#define RFM22_header_cntl2_synclen_3210 0x06 // Synchronization Word 3 followed by 2 followed by 1 followed by 0
|
||||
#define RFM22_header_cntl2_fixpklen 0x08 // Fix Packet Length. When fixpklen = 1 the packet length (pklen[7:0]) is not included in the header. When fixpklen = 0 the packet length is included in the header.
|
||||
#define RFM22_header_cntl2_hdlen_none 0x00 // no header
|
||||
#define RFM22_header_cntl2_hdlen_3 0x10 // header 3
|
||||
#define RFM22_header_cntl2_hdlen_32 0x20 // header 3 and 2
|
||||
#define RFM22_header_cntl2_hdlen_321 0x30 // header 3 and 2 and 1
|
||||
#define RFM22_header_cntl2_hdlen_3210 0x40 // header 3 and 2 and 1 and 0
|
||||
#define RFM22_header_cntl2_skipsyn 0x80 // If high, the system will ignore the syncword search timeout reset. The chip will not return to searching for Preamble, but instead will remain searching for Sync word.
|
||||
|
||||
#define RFM22_preamble_length 0x34 // R/W
|
||||
|
||||
#define RFM22_preamble_detection_ctrl1 0x35 // R/W
|
||||
#define RFM22_pre_det_ctrl1_preath_mask 0xF8 // Number of nibbles processed during detection.
|
||||
#define RFM22_pre_det_ctrl1_rssi_offset_mask 0x07 // Value added as offset to RSSI calculation. Every increment in this register results in an increment of +4 dB in the RSSI.
|
||||
|
||||
#define RFM22_sync_word3 0x36 // R/W
|
||||
#define RFM22_sync_word2 0x37 // R/W
|
||||
#define RFM22_sync_word1 0x38 // R/W
|
||||
#define RFM22_sync_word0 0x39 // R/W
|
||||
|
||||
#define RFM22_transmit_header3 0x3A // R/W
|
||||
#define RFM22_transmit_header2 0x3B // R/W
|
||||
#define RFM22_transmit_header1 0x3C // R/W
|
||||
#define RFM22_transmit_header0 0x3D // R/W
|
||||
|
||||
#define RFM22_transmit_packet_length 0x3E // R/W
|
||||
|
||||
#define RFM22_check_header3 0x3F // R/W
|
||||
#define RFM22_check_header2 0x40 // R/W
|
||||
#define RFM22_check_header1 0x41 // R/W
|
||||
#define RFM22_check_header0 0x42 // R/W
|
||||
|
||||
#define RFM22_header_enable3 0x43 // R/W
|
||||
#define RFM22_header_enable2 0x44 // R/W
|
||||
#define RFM22_header_enable1 0x45 // R/W
|
||||
#define RFM22_header_enable0 0x46 // R/W
|
||||
|
||||
#define RFM22_received_header3 0x47 // R
|
||||
#define RFM22_received_header2 0x48 // R
|
||||
#define RFM22_received_header1 0x49 // R
|
||||
#define RFM22_received_header0 0x4A // R
|
||||
|
||||
#define RFM22_received_packet_length 0x4B // R
|
||||
|
||||
#define RFM22_adc8_control 0x4F // R/W
|
||||
/*
|
||||
#define RFM22_analog_test_bus 0x50 // R/W
|
||||
#define RFM22_digital_test_bus 0x51 // R/W
|
||||
#define RFM22_tx_ramp_control 0x52 // R/W
|
||||
#define RFM22_pll_tune_time 0x53 // R/W
|
||||
|
||||
#define RFM22_calibration_control 0x55 // R/W
|
||||
|
||||
#define RFM22_modem_test 0x56 // R/W
|
||||
|
||||
#define RFM22_chargepump_test 0x57 // R/W
|
||||
#define RFM22_chargepump_current_trimming_override 0x58 // R/W
|
||||
|
||||
#define RFM22_divider_current_trimming 0x59 // R/W
|
||||
|
||||
#define RFM22_vco_current_trimming 0x5A // R/W
|
||||
#define RFM22_vco_calibration_override 0x5B // R/W
|
||||
|
||||
#define RFM22_synthersizer_test 0x5C // R/W
|
||||
|
||||
#define RFM22_block_enable_override1 0x5D // R/W
|
||||
#define RFM22_block_enable_override2 0x5E // R/W
|
||||
#define RFM22_block_enable_override3 0x5F // R/W
|
||||
*/
|
||||
#define RFM22_channel_filter_coeff_addr 0x60 // R/W
|
||||
#define RFM22_ch_fil_coeff_ad_inv_pre_th_mask 0xF0 //
|
||||
#define RFM22_ch_fil_coeff_ad_chfiladd_mask 0x0F // Channel Filter Coefficient Look-up Table Address. The address for channel filter coefficients used in the RX path.
|
||||
|
||||
|
||||
//#define RFM22_channel_filter_coeff_value 0x61 // R/W
|
||||
|
||||
#define RFM22_xtal_osc_por_ctrl 0x62 // R/W
|
||||
#define RFM22_xtal_osc_por_ctrl_pwst_mask 0xE0 // Internal Power States of the Chip.
|
||||
#define RFM22_xtal_osc_por_ctrl_clkhyst 0x10 // Clock Hysteresis Setting.
|
||||
#define RFM22_xtal_osc_por_ctrl_enbias2x 0x08 // 2 Times Higher Bias Current Enable.
|
||||
#define RFM22_xtal_osc_por_ctrl_enamp2x 0x04 // 2 Times Higher Amplification Enable.
|
||||
#define RFM22_xtal_osc_por_ctrl_bufovr 0x02 // Output Buffer Enable Override.
|
||||
#define RFM22_xtal_osc_por_ctrl_enbuf 0x01 // Output Buffer Enable.
|
||||
/*
|
||||
#define RFM22_rc_osc_coarse_calbration_override 0x63 // R/W
|
||||
#define RFM22_rc_osc_fine_calbration_override 0x64 // R/W
|
||||
|
||||
#define RFM22_ldo_control_override 0x65 // R/W
|
||||
#define RFM22_ldo_level_setting 0x66 // R/W
|
||||
|
||||
#define RFM22_deltasigma_adc_tuning1 0x67 // R/W
|
||||
#define RFM22_deltasigma_adc_tuning2 0x68 // R/W
|
||||
*/
|
||||
#define RFM22_agc_override1 0x69 // R/W
|
||||
#define RFM22_agc_ovr1_sgi 0x40 // AGC Loop, Set Gain Increase. If set to 0 then gain increasing will not be allowed. If set to 1 then gain increasing is allowed, default is 0.
|
||||
#define RFM22_agc_ovr1_agcen 0x20 // Automatic Gain Control Enable. When this bit is set then the result of the control can be read out from bits [4:0], otherwise the gain can be controlled manually by writing into bits [4:0].
|
||||
#define RFM22_agc_ovr1_lnagain 0x10 // LNA Gain Select. 0 = min gain = 5dB, 1 = max gain = 25 dB.
|
||||
#define RFM22_agc_ovr1_pga_mask 0x0F // PGA Gain Override Value.
|
||||
|
||||
//#define RFM22_agc_override2 0x6A // R/W
|
||||
|
||||
//#define RFM22_gfsk_fir_coeff_addr 0x6B // R/W
|
||||
//#define RFM22_gfsk_fir_coeff_value 0x6C // R/W
|
||||
|
||||
#define RFM22_tx_power 0x6D // R/W
|
||||
#define RFM22_tx_pwr_txpow_0 0x00 // +1dBm .. 1.25mW
|
||||
#define RFM22_tx_pwr_txpow_1 0x01 // +2dBm .. 1.6mW
|
||||
#define RFM22_tx_pwr_txpow_2 0x02 // +5dBm .. 3.16mW
|
||||
#define RFM22_tx_pwr_txpow_3 0x03 // +8dBm .. 6.3mW
|
||||
#define RFM22_tx_pwr_txpow_4 0x04 // +11dBm .. 12.6mW
|
||||
#define RFM22_tx_pwr_txpow_5 0x05 // +14dBm .. 25mW
|
||||
#define RFM22_tx_pwr_txpow_6 0x06 // +17dBm .. 50mW
|
||||
#define RFM22_tx_pwr_txpow_7 0x07 // +20dBm .. 100mW
|
||||
#define RFM22_tx_pwr_lna_sw 0x08 // LNA Switch Controller. If set, lna_sw control from the digital will go high during TX modes, and low during other times. If reset, the digital control signal is low at all times.
|
||||
#define RFM22_tx_pwr_papeaklvl_0 0x10 // " "
|
||||
#define RFM22_tx_pwr_papeaklvl_1 0x20 // PA Peak Detect Level (direct from register). 00 = 6.5, 01 = 7, 10 = 7.5, 11 = 8, 00 = default
|
||||
#define RFM22_tx_pwr_papeaken 0x40 // PA Peak Detector Enable.
|
||||
#define RFM22_tx_pwr_papeakval 0x80 // PA Peak Detector Value Read Register. Reading a 1 in this register when the papeaken=1 then the PA drain voltage is too high and the match network needs adjusting for optimal efficiency.
|
||||
|
||||
#define RFM22_tx_data_rate1 0x6E // R/W
|
||||
#define RFM22_tx_data_rate0 0x6F // R/W
|
||||
|
||||
#define RFM22_modulation_mode_control1 0x70 // R/W
|
||||
#define RFM22_mmc1_enwhite 0x01 // Data Whitening is Enabled if this bit is set.
|
||||
#define RFM22_mmc1_enmanch 0x02 // Manchester Coding is Enabled if this bit is set.
|
||||
#define RFM22_mmc1_enmaninv 0x04 // Manchester Data Inversion is Enabled if this bit is set.
|
||||
#define RFM22_mmc1_manppol 0x08 // Manchester Preamble Polarity (will transmit a series of 1 if set, or series of 0 if reset).
|
||||
#define RFM22_mmc1_enphpwdn 0x10 // If set, the Packet Handler will be powered down when chip is in low power mode.
|
||||
#define RFM22_mmc1_txdtrtscale 0x20 // This bit should be set for Data Rates below 30 kbps.
|
||||
|
||||
#define RFM22_modulation_mode_control2 0x71 // R/W
|
||||
#define RFM22_mmc2_modtyp_mask 0x03 // Modulation type.
|
||||
#define RFM22_mmc2_modtyp_none 0x00 //
|
||||
#define RFM22_mmc2_modtyp_ook 0x01 //
|
||||
#define RFM22_mmc2_modtyp_fsk 0x02 //
|
||||
#define RFM22_mmc2_modtyp_gfsk 0x03 //
|
||||
#define RFM22_mmc2_fd 0x04 // MSB of Frequency Deviation Setting, see "Register 72h. Frequency Deviation".
|
||||
#define RFM22_mmc2_eninv 0x08 // Invert TX and RX Data.
|
||||
#define RFM22_mmc2_dtmod_mask 0x30 // Modulation source.
|
||||
#define RFM22_mmc2_dtmod_dm_gpio 0x00 //
|
||||
#define RFM22_mmc2_dtmod_dm_sdi 0x10 //
|
||||
#define RFM22_mmc2_dtmod_fifo 0x20 //
|
||||
#define RFM22_mmc2_dtmod_pn9 0x30 //
|
||||
#define RFM22_mmc2_trclk_mask 0xC0 // TX Data Clock Configuration.
|
||||
#define RFM22_mmc2_trclk_clk_none 0x00 //
|
||||
#define RFM22_mmc2_trclk_clk_gpio 0x40 //
|
||||
#define RFM22_mmc2_trclk_clk_sdo 0x80 //
|
||||
#define RFM22_mmc2_trclk_clk_nirq 0xC0 //
|
||||
|
||||
#define RFM22_frequency_deviation 0x72 // R/W
|
||||
|
||||
#define RFM22_frequency_offset1 0x73 // R/W
|
||||
#define RFM22_frequency_offset2 0x74 // R/W
|
||||
|
||||
#define RFM22_frequency_band_select 0x75 // R/W
|
||||
#define RFM22_fb_mask 0x1F
|
||||
#define RFM22_fbs_hbsel 0x20
|
||||
#define RFM22_fbs_sbse 0x40
|
||||
|
||||
#define RFM22_nominal_carrier_frequency1 0x76 // R/W
|
||||
#define RFM22_nominal_carrier_frequency0 0x77 // R/W
|
||||
|
||||
#define RFM22_frequency_hopping_channel_select 0x79 // R/W
|
||||
#define RFM22_frequency_hopping_step_size 0x7A // R/W
|
||||
|
||||
#define RFM22_tx_fifo_control1 0x7C // R/W .. TX FIFO Almost Full Threshold (0 - 63)
|
||||
#define RFM22_tx_fifo_control1_mask 0x3F
|
||||
|
||||
#define RFM22_tx_fifo_control2 0x7D // R/W .. TX FIFO Almost Empty Threshold (0 - 63)
|
||||
#define RFM22_tx_fifo_control2_mask 0x3F
|
||||
|
||||
#define RFM22_rx_fifo_control 0x7E // R/W .. RX FIFO Almost Full Threshold (0 - 63)
|
||||
#define RFM22_rx_fifo_control_mask 0x3F
|
||||
|
||||
#define RFM22_fifo_access 0x7F // R/W
|
||||
|
||||
// ************************************
|
||||
|
||||
typedef int16_t ( *t_rfm22_TxDataByteCallback ) (void);
|
||||
typedef bool ( *t_rfm22_RxDataCallback ) (void *data, uint8_t len);
|
||||
|
||||
// ************************************
|
||||
|
||||
uint32_t rfm22_minFrequency(void);
|
||||
uint32_t rfm22_maxFrequency(void);
|
||||
|
||||
void rfm22_setNominalCarrierFrequency(uint32_t frequency_hz);
|
||||
uint32_t rfm22_getNominalCarrierFrequency(void);
|
||||
|
||||
float rfm22_getFrequencyStepSize(void);
|
||||
|
||||
void rfm22_setFreqHopChannel(uint8_t channel);
|
||||
uint8_t rfm22_freqHopChannel(void);
|
||||
|
||||
uint32_t rfm22_freqHopSize(void);
|
||||
|
||||
void rfm22_setDatarate(uint32_t datarate_bps, bool data_whitening);
|
||||
uint32_t rfm22_getDatarate(void);
|
||||
|
||||
void rfm22_setRxMode(uint8_t mode, bool multi_packet_mode);
|
||||
|
||||
int16_t rfm22_getRSSI(void);
|
||||
|
||||
int16_t rfm22_receivedRSSI(void);
|
||||
int32_t rfm22_receivedAFCHz(void);
|
||||
uint16_t rfm22_receivedLength(void);
|
||||
uint8_t * rfm22_receivedPointer(void);
|
||||
void rfm22_receivedDone(void);
|
||||
|
||||
int32_t rfm22_sendData(void *data, uint16_t length, bool send_immediately);
|
||||
|
||||
void rfm22_setFreqCalibration(uint8_t value);
|
||||
uint8_t rfm22_getFreqCalibration(void);
|
||||
|
||||
void rfm22_setTxPower(uint8_t tx_pwr);
|
||||
uint8_t rfm22_getTxPower(void);
|
||||
|
||||
void rfm22_setTxStream(void); // TEST ONLY
|
||||
|
||||
void rfm22_setTxNormal(void);
|
||||
void rfm22_setTxCarrierMode(void);
|
||||
void rfm22_setTxPNMode(void);
|
||||
|
||||
int8_t rfm22_currentMode(void);
|
||||
bool rfm22_transmitting(void);
|
||||
|
||||
bool rfm22_channelIsClear(void);
|
||||
|
||||
bool rfm22_txReady(void);
|
||||
|
||||
void rfm22_1ms_tick(void);
|
||||
void rfm22_process(void);
|
||||
|
||||
void rfm22_TxDataByte_SetCallback(t_rfm22_TxDataByteCallback new_function);
|
||||
void rfm22_RxData_SetCallback(t_rfm22_RxDataCallback new_function);
|
||||
|
||||
int rfm22_init_scan_spectrum(uint32_t min_frequency_hz, uint32_t max_frequency_hz);
|
||||
int rfm22_init_tx_stream(uint32_t min_frequency_hz, uint32_t max_frequency_hz);
|
||||
int rfm22_init_rx_stream(uint32_t min_frequency_hz, uint32_t max_frequency_hz);
|
||||
int rfm22_init_normal(uint32_t min_frequency_hz, uint32_t max_frequency_hz, uint32_t freq_hop_step_size);
|
||||
|
||||
// ************************************
|
||||
|
||||
#endif
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup PIOS PIOS Core hardware abstraction layer
|
||||
* @{
|
||||
* @addtogroup PIOS_RFM22B Radio Functions
|
||||
* @brief PIOS interface for RFM22B Radio
|
||||
* @{
|
||||
*
|
||||
* @file pios_rfm22b_priv.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @brief RFM22B private definitions.
|
||||
* @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_PRIV_H
|
||||
#define PIOS_RFM22B_PRIV_H
|
||||
|
||||
#include <pios.h>
|
||||
#include "fifo_buffer.h"
|
||||
#include "pios_rfm22b.h"
|
||||
|
||||
extern const struct pios_com_driver pios_rfm22b_com_driver;
|
||||
|
||||
// ************************************
|
||||
|
||||
#define RFM22_DEVICE_VERSION_V2 0x02
|
||||
#define RFM22_DEVICE_VERSION_A0 0x04
|
||||
#define RFM22_DEVICE_VERSION_B1 0x06
|
||||
|
||||
// ************************************
|
||||
|
||||
#define RFM22_MIN_CARRIER_FREQUENCY_HZ 240000000ul
|
||||
#define RFM22_MAX_CARRIER_FREQUENCY_HZ 930000000ul
|
||||
|
||||
// ************************************
|
||||
|
||||
enum { RX_SCAN_SPECTRUM = 0,
|
||||
RX_WAIT_PREAMBLE_MODE,
|
||||
RX_WAIT_SYNC_MODE,
|
||||
RX_DATA_MODE,
|
||||
TX_DATA_MODE,
|
||||
TX_STREAM_MODE,
|
||||
TX_CARRIER_MODE,
|
||||
TX_PN_MODE};
|
||||
|
||||
// ************************************
|
||||
|
||||
#define BIT0 (1u << 0)
|
||||
#define BIT1 (1u << 1)
|
||||
#define BIT2 (1u << 2)
|
||||
#define BIT3 (1u << 3)
|
||||
#define BIT4 (1u << 4)
|
||||
#define BIT5 (1u << 5)
|
||||
#define BIT6 (1u << 6)
|
||||
#define BIT7 (1u << 7)
|
||||
|
||||
// ************************************
|
||||
|
||||
#define RFM22_DEVICE_TYPE 0x00 // R
|
||||
#define RFM22_DT_MASK 0x1F
|
||||
|
||||
#define RFM22_DEVICE_VERSION 0x01 // R
|
||||
#define RFM22_DV_MASK 0x1F
|
||||
|
||||
#define RFM22_device_status 0x02 // R
|
||||
#define RFM22_ds_cps_mask 0x03 // Chip Power State mask
|
||||
#define RFM22_ds_cps_idle 0x00 // IDLE Chip Power State
|
||||
#define RFM22_ds_cps_rx 0x01 // RX Chip Power State
|
||||
#define RFM22_ds_cps_tx 0x02 // TX Chip Power State
|
||||
//#define RFM22_ds_lockdet 0x04 //
|
||||
//#define RFM22_ds_freqerr 0x08 //
|
||||
#define RFM22_ds_headerr 0x10 // Header Error Status. Indicates if the received packet has a header check error
|
||||
#define RFM22_ds_rxffem 0x20 // RX FIFO Empty Status
|
||||
#define RFM22_ds_ffunfl 0x40 // RX/TX FIFO Underflow Status
|
||||
#define RFM22_ds_ffovfl 0x80 // RX/TX FIFO Overflow Status
|
||||
|
||||
#define RFM22_interrupt_status1 0x03 // R
|
||||
#define RFM22_is1_icrerror BIT0 // CRC Error. When set to 1 the cyclic redundancy check is failed.
|
||||
#define RFM22_is1_ipkvalid BIT1 // Valid Packet Received.When set to 1 a valid packet has been received.
|
||||
#define RFM22_is1_ipksent BIT2 // Packet Sent Interrupt. When set to1 a valid packet has been transmitted.
|
||||
#define RFM22_is1_iext BIT3 // External Interrupt. When set to 1 an interrupt occurred on one of the GPIO’s if it is programmed so. The status can be checked in register 0Eh. See GPIOx Configuration section for the details.
|
||||
#define RFM22_is1_irxffafull BIT4 // RX FIFO Almost Full.When set to 1 the RX FIFO has met its almost full threshold and needs to be read by the microcontroller.
|
||||
#define RFM22_is1_ixtffaem BIT5 // TX FIFO Almost Empty. When set to 1 the TX FIFO is almost empty and needs to be filled.
|
||||
#define RFM22_is1_itxffafull BIT6 // TX FIFO Almost Full. When set to 1 the TX FIFO has met its almost full threshold and needs to be transmitted.
|
||||
#define RFM22_is1_ifferr BIT7 // FIFO Underflow/Overflow Error. When set to 1 the TX or RX FIFO has overflowed or underflowed.
|
||||
|
||||
#define RFM22_interrupt_status2 0x04 // R
|
||||
#define RFM22_is2_ipor BIT0 // Power-on-Reset (POR). When the chip detects a Power on Reset above the desired setting this bit will be set to 1.
|
||||
#define RFM22_is2_ichiprdy BIT1 // Chip Ready (XTAL). When a chip ready event has been detected this bit will be set to 1.
|
||||
#define RFM22_is2_ilbd BIT2 // Low Battery Detect. When a low battery event is been detected this bit will be set to 1. This interrupt event is saved even if it is not enabled by the mask register bit and causes an interrupt after it is enabled.
|
||||
#define RFM22_is2_iwut BIT3 // Wake-Up-Timer. On the expiration of programmed wake-up timer this bit will be set to 1.
|
||||
#define RFM22_is2_irssi BIT4 // RSSI. When RSSI level exceeds the programmed threshold this bit will be set to 1.
|
||||
#define RFM22_is2_ipreainval BIT5 // Invalid Preamble Detected. When the preamble is not found within a period of time set by the invalid preamble detection threshold in Register 54h, this bit will be set to 1.
|
||||
#define RFM22_is2_ipreaval BIT6 // Valid Preamble Detected. When a preamble is detected this bit will be set to 1.
|
||||
#define RFM22_is2_iswdet BIT7 // Sync Word Detected. When a sync word is detected this bit will be set to 1.
|
||||
|
||||
#define RFM22_interrupt_enable1 0x05 // R/W
|
||||
#define RFM22_ie1_encrcerror BIT0 // Enable CRC Error. When set to 1 the CRC Error interrupt will be enabled.
|
||||
#define RFM22_ie1_enpkvalid BIT1 // Enable Valid Packet Received. When ipkvalid = 1 the Valid Packet Received Interrupt will be enabled.
|
||||
#define RFM22_ie1_enpksent BIT2 // Enable Packet Sent. When ipksent =1 the Packet Sense Interrupt will be enabled.
|
||||
#define RFM22_ie1_enext BIT3 // Enable External Interrupt. When set to 1 the External Interrupt will be enabled.
|
||||
#define RFM22_ie1_enrxffafull BIT4 // Enable RX FIFO Almost Full. When set to 1 the RX FIFO Almost Full interrupt will be enabled.
|
||||
#define RFM22_ie1_entxffaem BIT5 // Enable TX FIFO Almost Empty. When set to 1 the TX FIFO Almost Empty interrupt will be enabled.
|
||||
#define RFM22_ie1_entxffafull BIT6 // Enable TX FIFO Almost Full. When set to 1 the TX FIFO Almost Full interrupt will be enabled.
|
||||
#define RFM22_ie1_enfferr BIT7 // Enable FIFO Underflow/Overflow. When set to 1 the FIFO Underflow/Overflow interrupt will be enabled.
|
||||
|
||||
#define RFM22_interrupt_enable2 0x06 // R/W
|
||||
#define RFM22_ie2_enpor BIT0 // Enable POR. When set to 1 the POR interrupt will be enabled.
|
||||
#define RFM22_ie2_enchiprdy BIT1 // Enable Chip Ready (XTAL). When set to 1 the Chip Ready interrupt will be enabled.
|
||||
#define RFM22_ie2_enlbd BIT2 // Enable Low Battery Detect. When set to 1 the Low Battery Detect interrupt will be enabled.
|
||||
#define RFM22_ie2_enwut BIT3 // Enable Wake-Up Timer. When set to 1 the Wake-Up Timer interrupt will be enabled.
|
||||
#define RFM22_ie2_enrssi BIT4 // Enable RSSI. When set to 1 the RSSI Interrupt will be enabled.
|
||||
#define RFM22_ie2_enpreainval BIT5 // Enable Invalid Preamble Detected. When mpreadet =1 the Invalid Preamble Detected Interrupt will be enabled.
|
||||
#define RFM22_ie2_enpreaval BIT6 // Enable Valid Preamble Detected. When mpreadet =1 the Valid Preamble Detected Interrupt will be enabled.
|
||||
#define RFM22_ie2_enswdet BIT7 // Enable Sync Word Detected. When mpreadet =1 the Preamble Detected Interrupt will be enabled.
|
||||
|
||||
#define RFM22_op_and_func_ctrl1 0x07 // R/W
|
||||
#define RFM22_opfc1_xton 0x01 // READY Mode (Xtal is ON).
|
||||
#define RFM22_opfc1_pllon 0x02 // TUNE Mode (PLL is ON). When pllon = 1 the PLL will remain enabled in Idle State. This will for faster turn-around time at the cost of increased current consumption in Idle State.
|
||||
#define RFM22_opfc1_rxon 0x04 // RX on in Manual Receiver Mode. Automatically cleared if Multiple Packets config. is disabled and a valid packet received.
|
||||
#define RFM22_opfc1_txon 0x08 // TX on in Manual Transmit Mode. Automatically cleared in FIFO mode once the packet is sent. Transmission can be aborted during packet transmission, however, when no data has been sent yet, transmission can only be aborted after the device is programmed to “unmodulated carrier” ("Register 71h. Modulation Mode Control 2").
|
||||
#define RFM22_opfc1_x32ksel 0x10 // 32,768 kHz Crystal Oscillator Select. 0: RC oscillator 1: 32 kHz crystal
|
||||
#define RFM22_opfc1_enwt 0x20 // Enable Wake-Up-Timer. Enabled when enwt = 1. If the Wake-up-Timer function is enabled it will operate in any mode and notify the microcontroller through the GPIO interrupt when the timer expires.
|
||||
#define RFM22_opfc1_enlbd 0x40 // Enable Low Battery Detect. When this bit is set to 1 the Low Battery Detector circuit and threshold comparison will be enabled.
|
||||
#define RFM22_opfc1_swres 0x80 // Software Register Reset Bit. This bit may be used to reset all registers simultaneously to a DEFAULT state, without the need for sequentially writing to each individual register. The RESET is accomplished by setting swres = 1. This bit will be automatically cleared.
|
||||
|
||||
#define RFM22_op_and_func_ctrl2 0x08 // R/W
|
||||
#define RFM22_opfc2_ffclrtx 0x01 // TX FIFO Reset/Clear. This has to be a two writes operation: Setting ffclrtx =1 followed by ffclrtx = 0 will clear the contents of the TX FIFO.
|
||||
#define RFM22_opfc2_ffclrrx 0x02 // RX FIFO Reset/Clear. This has to be a two writes operation: Setting ffclrrx =1 followed by ffclrrx = 0 will clear the contents of the RX FIFO.
|
||||
#define RFM22_opfc2_enldm 0x04 // Enable Low Duty Cycle Mode. If this bit is set to 1 then the chip turns on the RX regularly. The frequency should be set in the Wake-Up Timer Period register, while the minimum ON time should be set in the Low-Duty Cycle Mode Duration register. The FIFO mode should be enabled also.
|
||||
#define RFM22_opfc2_autotx 0x08 // Automatic Transmission. When autotx = 1 the transceiver will enter automatically TX State when the FIFO is almost full. When the FIFO is empty it will automatically return to the Idle State.
|
||||
#define RFM22_opfc2_rxmpk 0x10 // RX Multi Packet. When the chip is selected to use FIFO Mode (dtmod[1:0]) and RX Packet Handling (enpacrx) then it will fill up the FIFO with multiple valid packets if this bit is set, otherwise the transceiver will automatically leave the RX State after the first valid packet has been received.
|
||||
#define RFM22_opfc2_antdiv_mask 0xE0 // Enable Antenna Diversity. The GPIO must be configured for Antenna Diversity for the algorithm to work properly.
|
||||
|
||||
#define RFM22_xtal_osc_load_cap 0x09 // R/W
|
||||
#define RFM22_xolc_xlc_mask 0x7F // Tuning Capacitance for the 30 MHz XTAL.
|
||||
#define RFM22_xolc_xtalshft 0x80 // Additional capacitance to course shift the frequency if xlc[6:0] is not sufficient. Not binary with xlc[6:0].
|
||||
|
||||
#define RFM22_cpu_output_clk 0x0A // R/W
|
||||
#define RFM22_coc_30MHz 0x00
|
||||
#define RFM22_coc_15MHz 0x01
|
||||
#define RFM22_coc_10MHz 0x02
|
||||
#define RFM22_coc_4MHz 0x03
|
||||
#define RFM22_coc_3MHz 0x04
|
||||
#define RFM22_coc_2MHz 0x05
|
||||
#define RFM22_coc_1MHz 0x06
|
||||
#define RFM22_coc_32768Hz 0x07
|
||||
#define RFM22_coc_enlfc 0x08
|
||||
#define RFM22_coc_0cycle 0x00
|
||||
#define RFM22_coc_128cycles 0x10
|
||||
#define RFM22_coc_256cycles 0x20
|
||||
#define RFM22_coc_512cycles 0x30
|
||||
|
||||
#define RFM22_gpio0_config 0x0B // R/W
|
||||
#define RFM22_gpio0_config_por 0x00 // Power-On-Reset (output)
|
||||
#define RFM22_gpio0_config_wut 0x01 // Wake-Up Timer: 1 when WUT has expired (output)
|
||||
#define RFM22_gpio0_config_lbd 0x02 // Low Battery Detect: 1 when battery is below threshold setting (output)
|
||||
#define RFM22_gpio0_config_ddi 0x03 // Direct Digital Input
|
||||
#define RFM22_gpio0_config_eife 0x04 // External Interrupt, falling edge (input)
|
||||
#define RFM22_gpio0_config_eire 0x05 // External Interrupt, rising edge (input)
|
||||
#define RFM22_gpio0_config_eisc 0x06 // External Interrupt, state change (input)
|
||||
#define RFM22_gpio0_config_ai 0x07 // ADC Analog Input
|
||||
#define RFM22_gpio0_config_atni 0x08 // Reserved (Analog Test N Input)
|
||||
#define RFM22_gpio0_config_atpi 0x09 // Reserved (Analog Test P Input)
|
||||
#define RFM22_gpio0_config_ddo 0x0A // Direct Digital Output
|
||||
#define RFM22_gpio0_config_dto 0x0B // Reserved (Digital Test Output)
|
||||
#define RFM22_gpio0_config_atno 0x0C // Reserved (Analog Test N Output)
|
||||
#define RFM22_gpio0_config_atpo 0x0D // Reserved (Analog Test P Output)
|
||||
#define RFM22_gpio0_config_rv 0xOE // Reference Voltage (output)
|
||||
#define RFM22_gpio0_config_dclk 0x0F // TX/RX Data CLK output to be used in conjunction with TX/RX Data pin (output)
|
||||
#define RFM22_gpio0_config_txd 0x10 // TX Data input for direct modulation (input)
|
||||
#define RFM22_gpio0_config_err 0x11 // External Retransmission Request (input)
|
||||
#define RFM22_gpio0_config_txstate 0x12 // TX State (output)
|
||||
#define RFM22_gpio0_config_txfifoaf 0x13 // TX FIFO Almost Full (output)
|
||||
#define RFM22_gpio0_config_rxd 0x14 // RX Data (output)
|
||||
#define RFM22_gpio0_config_rxstate 0x15 // RX State (output)
|
||||
#define RFM22_gpio0_config_rxfifoaf 0x16 // RX FIFO Almost Full (output)
|
||||
#define RFM22_gpio0_config_antswt1 0x17 // Antenna 1 Switch used for antenna diversity (output)
|
||||
#define RFM22_gpio0_config_antswt2 0x18 // Antenna 2 Switch used for antenna diversity (output)
|
||||
#define RFM22_gpio0_config_vpd 0x19 // Valid Preamble Detected (output)
|
||||
#define RFM22_gpio0_config_ipd 0x1A // Invalid Preamble Detected (output)
|
||||
#define RFM22_gpio0_config_swd 0x1B // Sync Word Detected (output)
|
||||
#define RFM22_gpio0_config_cca 0x1C // Clear Channel Assessment (output)
|
||||
#define RFM22_gpio0_config_vdd 0x1D // VDD
|
||||
#define RFM22_gpio0_config_pup 0x20
|
||||
#define RFM22_gpio0_config_drv0 0x00 // output drive level
|
||||
#define RFM22_gpio0_config_drv1 0x40 // output drive level
|
||||
#define RFM22_gpio0_config_drv2 0x80 // output drive level
|
||||
#define RFM22_gpio0_config_drv3 0xC0 // output drive level
|
||||
|
||||
#define RFM22_gpio1_config 0x0C // R/W
|
||||
#define RFM22_gpio1_config_ipor 0x00 // Inverted Power-On-Reset (output)
|
||||
#define RFM22_gpio1_config_wut 0x01 // Wake-Up Timer: 1 when WUT has expired (output)
|
||||
#define RFM22_gpio1_config_lbd 0x02 // Low Battery Detect: 1 when battery is below threshold setting (output)
|
||||
#define RFM22_gpio1_config_ddi 0x03 // Direct Digital Input
|
||||
#define RFM22_gpio1_config_eife 0x04 // External Interrupt, falling edge (input)
|
||||
#define RFM22_gpio1_config_eire 0x05 // External Interrupt, rising edge (input)
|
||||
#define RFM22_gpio1_config_eisc 0x06 // External Interrupt, state change (input)
|
||||
#define RFM22_gpio1_config_ai 0x07 // ADC Analog Input
|
||||
#define RFM22_gpio1_config_atni 0x08 // Reserved (Analog Test N Input)
|
||||
#define RFM22_gpio1_config_atpi 0x09 // Reserved (Analog Test P Input)
|
||||
#define RFM22_gpio1_config_ddo 0x0A // Direct Digital Output
|
||||
#define RFM22_gpio1_config_dto 0x0B // Reserved (Digital Test Output)
|
||||
#define RFM22_gpio1_config_atno 0x0C // Reserved (Analog Test N Output)
|
||||
#define RFM22_gpio1_config_atpo 0x0D // Reserved (Analog Test P Output)
|
||||
#define RFM22_gpio1_config_rv 0xOE // Reference Voltage (output)
|
||||
#define RFM22_gpio1_config_dclk 0x0F // TX/RX Data CLK output to be used in conjunction with TX/RX Data pin (output)
|
||||
#define RFM22_gpio1_config_txd 0x10 // TX Data input for direct modulation (input)
|
||||
#define RFM22_gpio1_config_err 0x11 // External Retransmission Request (input)
|
||||
#define RFM22_gpio1_config_txstate 0x12 // TX State (output)
|
||||
#define RFM22_gpio1_config_txfifoaf 0x13 // TX FIFO Almost Full (output)
|
||||
#define RFM22_gpio1_config_rxd 0x14 // RX Data (output)
|
||||
#define RFM22_gpio1_config_rxstate 0x15 // RX State (output)
|
||||
#define RFM22_gpio1_config_rxfifoaf 0x16 // RX FIFO Almost Full (output)
|
||||
#define RFM22_gpio1_config_antswt1 0x17 // Antenna 1 Switch used for antenna diversity (output)
|
||||
#define RFM22_gpio1_config_antswt2 0x18 // Antenna 2 Switch used for antenna diversity (output)
|
||||
#define RFM22_gpio1_config_vpd 0x19 // Valid Preamble Detected (output)
|
||||
#define RFM22_gpio1_config_ipd 0x1A // Invalid Preamble Detected (output)
|
||||
#define RFM22_gpio1_config_swd 0x1B // Sync Word Detected (output)
|
||||
#define RFM22_gpio1_config_cca 0x1C // Clear Channel Assessment (output)
|
||||
#define RFM22_gpio1_config_vdd 0x1D // VDD
|
||||
#define RFM22_gpio1_config_pup 0x20
|
||||
#define RFM22_gpio1_config_drv0 0x00 // output drive level
|
||||
#define RFM22_gpio1_config_drv1 0x40 // output drive level
|
||||
#define RFM22_gpio1_config_drv2 0x80 // output drive level
|
||||
#define RFM22_gpio1_config_drv3 0xC0 // output drive level
|
||||
|
||||
#define RFM22_gpio2_config 0x0D // R/W
|
||||
#define RFM22_gpio2_config_mc 0x00 // Microcontroller Clock (output)
|
||||
#define RFM22_gpio2_config_wut 0x01 // Wake-Up Timer: 1 when WUT has expired (output)
|
||||
#define RFM22_gpio2_config_lbd 0x02 // Low Battery Detect: 1 when battery is below threshold setting (output)
|
||||
#define RFM22_gpio2_config_ddi 0x03 // Direct Digital Input
|
||||
#define RFM22_gpio2_config_eife 0x04 // External Interrupt, falling edge (input)
|
||||
#define RFM22_gpio2_config_eire 0x05 // External Interrupt, rising edge (input)
|
||||
#define RFM22_gpio2_config_eisc 0x06 // External Interrupt, state change (input)
|
||||
#define RFM22_gpio2_config_ai 0x07 // ADC Analog Input
|
||||
#define RFM22_gpio2_config_atni 0x08 // Reserved (Analog Test N Input)
|
||||
#define RFM22_gpio2_config_atpi 0x09 // Reserved (Analog Test P Input)
|
||||
#define RFM22_gpio2_config_ddo 0x0A // Direct Digital Output
|
||||
#define RFM22_gpio2_config_dto 0x0B // Reserved (Digital Test Output)
|
||||
#define RFM22_gpio2_config_atno 0x0C // Reserved (Analog Test N Output)
|
||||
#define RFM22_gpio2_config_atpo 0x0D // Reserved (Analog Test P Output)
|
||||
#define RFM22_gpio2_config_rv 0xOE // Reference Voltage (output)
|
||||
#define RFM22_gpio2_config_dclk 0x0F // TX/RX Data CLK output to be used in conjunction with TX/RX Data pin (output)
|
||||
#define RFM22_gpio2_config_txd 0x10 // TX Data input for direct modulation (input)
|
||||
#define RFM22_gpio2_config_err 0x11 // External Retransmission Request (input)
|
||||
#define RFM22_gpio2_config_txstate 0x12 // TX State (output)
|
||||
#define RFM22_gpio2_config_txfifoaf 0x13 // TX FIFO Almost Full (output)
|
||||
#define RFM22_gpio2_config_rxd 0x14 // RX Data (output)
|
||||
#define RFM22_gpio2_config_rxstate 0x15 // RX State (output)
|
||||
#define RFM22_gpio2_config_rxfifoaf 0x16 // RX FIFO Almost Full (output)
|
||||
#define RFM22_gpio2_config_antswt1 0x17 // Antenna 1 Switch used for antenna diversity (output)
|
||||
#define RFM22_gpio2_config_antswt2 0x18 // Antenna 2 Switch used for antenna diversity (output)
|
||||
#define RFM22_gpio2_config_vpd 0x19 // Valid Preamble Detected (output)
|
||||
#define RFM22_gpio2_config_ipd 0x1A // Invalid Preamble Detected (output)
|
||||
#define RFM22_gpio2_config_swd 0x1B // Sync Word Detected (output)
|
||||
#define RFM22_gpio2_config_cca 0x1C // Clear Channel Assessment (output)
|
||||
#define RFM22_gpio2_config_vdd 0x1D // VDD
|
||||
#define RFM22_gpio2_config_pup 0x20
|
||||
#define RFM22_gpio2_config_drv0 0x00 // output drive level
|
||||
#define RFM22_gpio2_config_drv1 0x40 // output drive level
|
||||
#define RFM22_gpio2_config_drv2 0x80 // output drive level
|
||||
#define RFM22_gpio2_config_drv3 0xC0 // output drive level
|
||||
|
||||
#define RFM22_io_port_config 0x0E // R/W
|
||||
#define RFM22_io_port_extitst2 0x40 // External Interrupt Status. If the GPIO2 is programmed to be external interrupt sources then the status can be read here.
|
||||
#define RFM22_io_port_extitst1 0x20 // External Interrupt Status. If the GPIO1 is programmed to be external interrupt sources then the status can be read here.
|
||||
#define RFM22_io_port_extitst0 0x10 // External Interrupt Status. If the GPIO0 is programmed to be external interrupt sources then the status can be read here.
|
||||
#define RFM22_io_port_itsdo 0x08 // Interrupt Request Output on the SDO Pin. nIRQ output is present on the SDO pin if this bit is set and the nSEL input is inactive (high).
|
||||
#define RFM22_io_port_dio2 0x04 // Direct I/O for GPIO2. If the GPIO2 is configured to be a direct output then the value on the GPIO pin can be set here. If the GPIO2 is configured to be a direct input then the value of the pin can be read here.
|
||||
#define RFM22_io_port_dio1 0x02 // Direct I/O for GPIO1. If the GPIO1 is configured to be a direct output then the value on the GPIO pin can be set here. If the GPIO1 is configured to be a direct input then the value of the pin can be read here.
|
||||
#define RFM22_io_port_dio0 0x01 // Direct I/O for GPIO0. If the GPIO0 is configured to be a direct output then the value on the GPIO pin can be set here. If the GPIO0 is configured to be a direct input then the value of the pin can be read here.
|
||||
#define RFM22_io_port_default 0x00 // GPIO pins are default
|
||||
|
||||
#define RFM22_adc_config 0x0F // R/W
|
||||
#define RFM22_ac_adcgain0 0x00
|
||||
#define RFM22_ac_adcgain1 0x01
|
||||
#define RFM22_ac_adcgain2 0x02
|
||||
#define RFM22_ac_adcgain3 0x03
|
||||
#define RFM22_ac_adcref_bg 0x00
|
||||
#define RFM22_ac_adcref_vdd3 0x08
|
||||
#define RFM22_ac_adcref_vdd2 0x0C
|
||||
#define RFM22_ac_adcsel_temp_sensor 0x00
|
||||
#define RFM22_ac_adcsel_gpio0 0x10
|
||||
#define RFM22_ac_adcsel_gpio1 0x20
|
||||
#define RFM22_ac_adcsel_gpio2 0x30
|
||||
#define RFM22_ac_adcsel_gpio01 0x40
|
||||
#define RFM22_ac_adcsel_gpio12 0x50
|
||||
#define RFM22_ac_adcsel_gpio02 0x60
|
||||
#define RFM22_ac_adcsel_gpio_gnd 0x70
|
||||
#define RFM22_ac_adcstartbusy 0x80
|
||||
|
||||
#define RFM22_adc_sensor_amp_offset 0x10 // R/W
|
||||
#define RFM22_asao_adcoffs_mask 0x0F // ADC Sensor Amplifier Offset. The offset can be calculated as Offset = adcoffs[2:0] x VDD/1000; MSB = adcoffs[3] = Sign bit.
|
||||
|
||||
#define RFM22_adc_value 0x11 // R .. Internal 8 bit ADC Output Value.
|
||||
|
||||
#define RFM22_temp_sensor_calib 0x12 // R/W
|
||||
#define RFM22_tsc_tstrim_mask 0x0F // Temperature Sensor Trim Value.
|
||||
#define RFM22_tsc_entstrim 0x10 // Temperature Sensor Trim Enable.
|
||||
#define RFM22_tsc_entsoffs 0x20 // Temperature Sensor Offset to Convert from K to ºC.
|
||||
#define RFM22_tsc_tsrange0 0x00 // Temperature Sensor Range Selection. –64C to +64C 0.5C resolution
|
||||
#define RFM22_tsc_tsrange1 0x40 // -40 to +85C with 1.0C resolution
|
||||
#define RFM22_tsc_tsrange2 0x80 // 0C to 85C with 0.5C resolution
|
||||
#define RFM22_tsc_tsrange3 0xC0 // -40F to 216F with 1.0F resolution
|
||||
|
||||
#define RFM22_temp_value_offset 0x13 // R/W
|
||||
|
||||
#define RFM22_wakeup_timer_period1 0x14 // R/W
|
||||
#define RFM22_wakeup_timer_period2 0x15 // R/W
|
||||
#define RFM22_wakeup_timer_period3 0x16 // R/W
|
||||
|
||||
#define RFM22_wakeup_timer_value1 0x17 // R
|
||||
#define RFM22_wakeup_timer_value2 0x18 // R
|
||||
|
||||
#define RFM22_low_dutycycle_mode_duration 0x19 // R/W
|
||||
#define RFM22_low_battery_detector_threshold 0x1A // R/W
|
||||
|
||||
#define RFM22_battery_volateg_level 0x1B // R
|
||||
|
||||
#define RFM22_if_filter_bandwidth 0x1C // R/W
|
||||
#define RFM22_iffbw_filset_mask 0x0F
|
||||
#define RFM22_iffbw_ndec_exp_mask 0x70
|
||||
#define RFM22_iffbw_dwn3_bypass 0x80
|
||||
|
||||
#define RFM22_afc_loop_gearshift_override 0x1D // R/W
|
||||
#define RFM22_afc_lp_gs_ovrd_afcgearl_mask 0x07 // AFC Low Gear Setting.
|
||||
#define RFM22_afc_lp_gs_ovrd_afcgearh_mask 0x38 // AFC High Gear Setting.
|
||||
#define RFM22_afc_lp_gs_ovrd_enafc 0x40 // AFC Enable.
|
||||
#define RFM22_afc_lp_gs_ovrd_afcbd 0x80 // If set, the tolerated AFC frequency error will be halved.
|
||||
|
||||
#define RFM22_afc_timing_control 0x1E // R/W
|
||||
|
||||
#define RFM22_clk_recovery_gearshift_override 0x1F // R/W
|
||||
#define RFM22_clk_recovery_oversampling_ratio 0x20 // R/W
|
||||
#define RFM22_clk_recovery_offset2 0x21 // R/W
|
||||
#define RFM22_clk_recovery_offset1 0x22 // R/W
|
||||
#define RFM22_clk_recovery_offset0 0x23 // R/W
|
||||
#define RFM22_clk_recovery_timing_loop_gain1 0x24 // R/W
|
||||
#define RFM22_clk_recovery_timing_loop_gain0 0x25 // R/W
|
||||
|
||||
#define RFM22_rssi 0x26 // R
|
||||
#define RFM22_rssi_threshold_clear_chan_indicator 0x27 // R/W
|
||||
|
||||
#define RFM22_antenna_diversity_register1 0x28 // R
|
||||
#define RFM22_antenna_diversity_register2 0x29 // R
|
||||
|
||||
#define RFM22_afc_limiter 0x2A // R/W .. AFC_pull_in_range = ±AFCLimiter[7:0] x (hbsel+1) x 625 Hz
|
||||
|
||||
#define RFM22_afc_correction_read 0x2B // R
|
||||
|
||||
#define RFM22_ook_counter_value1 0x2C // R/W
|
||||
#define RFM22_ook_counter_value2 0x2D // R/W
|
||||
|
||||
#define RFM22_slicer_peak_hold 0x2E // R/W
|
||||
|
||||
#define RFM22_data_access_control 0x30 // R/W
|
||||
#define RFM22_dac_crc_ccitt 0x00 //
|
||||
#define RFM22_dac_crc_crc16 0x01 //
|
||||
#define RFM22_dac_crc_iec16 0x02 //
|
||||
#define RFM22_dac_crc_biacheva 0x03 //
|
||||
#define RFM22_dac_encrc 0x04 // CRC Enable. Cyclic Redundancy Check generation is enabled if this bit is set.
|
||||
#define RFM22_dac_enpactx 0x08 // Enable Packet TX Handling. If FIFO Mode (dtmod = 10) is being used automatic packet handling may be enabled. Setting enpactx = 1 will enable automatic packet handling in the TX path. Register 30–4D allow for various configurations of the packet structure. Setting enpactx = 0 will not do any packet handling in the TX path. It will only transmit what is loaded to the FIFO.
|
||||
#define RFM22_dac_skip2ph 0x10 // Skip 2nd Phase of Preamble Detection. If set, we skip the second phase of the preamble detection (under certain conditions) if antenna diversity is enabled.
|
||||
#define RFM22_dac_crcdonly 0x20 // CRC Data Only Enable. When this bit is set to 1 the CRC is calculated on and checked against the packet data fields only.
|
||||
#define RFM22_dac_lsbfrst 0x40 // LSB First Enable. The LSB of the data will be transmitted/received first if this bit is set.
|
||||
#define RFM22_dac_enpacrx 0x80 // Enable Packet RX Handling. If FIFO Mode (dtmod = 10) is being used automatic packet handling may be enabled. Setting enpacrx = 1 will enable automatic packet handling in the RX path. Register 30–4D allow for various configurations of the packet structure. Setting enpacrx = 0 will not do any packet handling in the RX path. It will only receive everything after the sync word and fill up the RX FIFO.
|
||||
|
||||
#define RFM22_ezmac_status 0x31 // R
|
||||
#define RFM22_ezmac_status_pksent 0x01 // Packet Sent. A 1 a packet has been sent by the radio. (Same bit as in register 03, but reading it does not reset the IRQ)
|
||||
#define RFM22_ezmac_status_pktx 0x02 // Packet Transmitting. When 1 the radio is currently transmitting a packet.
|
||||
#define RFM22_ezmac_status_crcerror 0x04 // CRC Error. When 1 a Cyclic Redundancy Check error has been detected. (Same bit as in register 03, but reading it does not reset the IRQ)
|
||||
#define RFM22_ezmac_status_pkvalid 0x08 // Valid Packet Received. When a 1 a valid packet has been received by the receiver. (Same bit as in register 03, but reading it does not reset the IRQ)
|
||||
#define RFM22_ezmac_status_pkrx 0x10 // Packet Receiving. When 1 the radio is currently receiving a valid packet.
|
||||
#define RFM22_ezmac_status_pksrch 0x20 // Packet Searching. When 1 the radio is searching for a valid packet.
|
||||
#define RFM22_ezmac_status_rxcrc1 0x40 // If high, it indicates the last CRC received is all one’s. May indicated Transmitter underflow in case of CRC error.
|
||||
|
||||
#define RFM22_header_control1 0x32 // R/W
|
||||
#define RFM22_header_cntl1_bcen_none 0x00 // No broadcast address enable.
|
||||
#define RFM22_header_cntl1_bcen_0 0x10 // Broadcast address enable for header byte 0.
|
||||
#define RFM22_header_cntl1_bcen_1 0x20 // Broadcast address enable for header byte 1.
|
||||
#define RFM22_header_cntl1_bcen_2 0x40 // Broadcast address enable for header byte 2.
|
||||
#define RFM22_header_cntl1_bcen_3 0x80 // Broadcast address enable for header byte 3.
|
||||
#define RFM22_header_cntl1_hdch_none 0x00 // No Received Header check
|
||||
#define RFM22_header_cntl1_hdch_0 0x01 // Received Header check for byte 0.
|
||||
#define RFM22_header_cntl1_hdch_1 0x02 // Received Header check for byte 1.
|
||||
#define RFM22_header_cntl1_hdch_2 0x04 // Received Header check for byte 2.
|
||||
#define RFM22_header_cntl1_hdch_3 0x08 // Received Header check for byte 3.
|
||||
|
||||
#define RFM22_header_control2 0x33 // R/W
|
||||
#define RFM22_header_cntl2_prealen 0x01 // MSB of Preamble Length. See register Preamble Length.
|
||||
#define RFM22_header_cntl2_synclen_3 0x00 // Synchronization Word 3
|
||||
#define RFM22_header_cntl2_synclen_32 0x02 // Synchronization Word 3 followed by 2
|
||||
#define RFM22_header_cntl2_synclen_321 0x04 // Synchronization Word 3 followed by 2 followed by 1
|
||||
#define RFM22_header_cntl2_synclen_3210 0x06 // Synchronization Word 3 followed by 2 followed by 1 followed by 0
|
||||
#define RFM22_header_cntl2_fixpklen 0x08 // Fix Packet Length. When fixpklen = 1 the packet length (pklen[7:0]) is not included in the header. When fixpklen = 0 the packet length is included in the header.
|
||||
#define RFM22_header_cntl2_hdlen_none 0x00 // no header
|
||||
#define RFM22_header_cntl2_hdlen_3 0x10 // header 3
|
||||
#define RFM22_header_cntl2_hdlen_32 0x20 // header 3 and 2
|
||||
#define RFM22_header_cntl2_hdlen_321 0x30 // header 3 and 2 and 1
|
||||
#define RFM22_header_cntl2_hdlen_3210 0x40 // header 3 and 2 and 1 and 0
|
||||
#define RFM22_header_cntl2_skipsyn 0x80 // If high, the system will ignore the syncword search timeout reset. The chip will not return to searching for Preamble, but instead will remain searching for Sync word.
|
||||
|
||||
#define RFM22_preamble_length 0x34 // R/W
|
||||
|
||||
#define RFM22_preamble_detection_ctrl1 0x35 // R/W
|
||||
#define RFM22_pre_det_ctrl1_preath_mask 0xF8 // Number of nibbles processed during detection.
|
||||
#define RFM22_pre_det_ctrl1_rssi_offset_mask 0x07 // Value added as offset to RSSI calculation. Every increment in this register results in an increment of +4 dB in the RSSI.
|
||||
|
||||
#define RFM22_sync_word3 0x36 // R/W
|
||||
#define RFM22_sync_word2 0x37 // R/W
|
||||
#define RFM22_sync_word1 0x38 // R/W
|
||||
#define RFM22_sync_word0 0x39 // R/W
|
||||
|
||||
#define RFM22_transmit_header3 0x3A // R/W
|
||||
#define RFM22_transmit_header2 0x3B // R/W
|
||||
#define RFM22_transmit_header1 0x3C // R/W
|
||||
#define RFM22_transmit_header0 0x3D // R/W
|
||||
|
||||
#define RFM22_transmit_packet_length 0x3E // R/W
|
||||
|
||||
#define RFM22_check_header3 0x3F // R/W
|
||||
#define RFM22_check_header2 0x40 // R/W
|
||||
#define RFM22_check_header1 0x41 // R/W
|
||||
#define RFM22_check_header0 0x42 // R/W
|
||||
|
||||
#define RFM22_header_enable3 0x43 // R/W
|
||||
#define RFM22_header_enable2 0x44 // R/W
|
||||
#define RFM22_header_enable1 0x45 // R/W
|
||||
#define RFM22_header_enable0 0x46 // R/W
|
||||
|
||||
#define RFM22_received_header3 0x47 // R
|
||||
#define RFM22_received_header2 0x48 // R
|
||||
#define RFM22_received_header1 0x49 // R
|
||||
#define RFM22_received_header0 0x4A // R
|
||||
|
||||
#define RFM22_received_packet_length 0x4B // R
|
||||
|
||||
#define RFM22_adc8_control 0x4F // R/W
|
||||
/*
|
||||
#define RFM22_analog_test_bus 0x50 // R/W
|
||||
#define RFM22_digital_test_bus 0x51 // R/W
|
||||
#define RFM22_tx_ramp_control 0x52 // R/W
|
||||
#define RFM22_pll_tune_time 0x53 // R/W
|
||||
|
||||
#define RFM22_calibration_control 0x55 // R/W
|
||||
|
||||
#define RFM22_modem_test 0x56 // R/W
|
||||
|
||||
#define RFM22_chargepump_test 0x57 // R/W
|
||||
#define RFM22_chargepump_current_trimming_override 0x58 // R/W
|
||||
|
||||
#define RFM22_divider_current_trimming 0x59 // R/W
|
||||
|
||||
#define RFM22_vco_current_trimming 0x5A // R/W
|
||||
#define RFM22_vco_calibration_override 0x5B // R/W
|
||||
|
||||
#define RFM22_synthersizer_test 0x5C // R/W
|
||||
|
||||
#define RFM22_block_enable_override1 0x5D // R/W
|
||||
#define RFM22_block_enable_override2 0x5E // R/W
|
||||
#define RFM22_block_enable_override3 0x5F // R/W
|
||||
*/
|
||||
#define RFM22_channel_filter_coeff_addr 0x60 // R/W
|
||||
#define RFM22_ch_fil_coeff_ad_inv_pre_th_mask 0xF0 //
|
||||
#define RFM22_ch_fil_coeff_ad_chfiladd_mask 0x0F // Channel Filter Coefficient Look-up Table Address. The address for channel filter coefficients used in the RX path.
|
||||
|
||||
|
||||
//#define RFM22_channel_filter_coeff_value 0x61 // R/W
|
||||
|
||||
#define RFM22_xtal_osc_por_ctrl 0x62 // R/W
|
||||
#define RFM22_xtal_osc_por_ctrl_pwst_mask 0xE0 // Internal Power States of the Chip.
|
||||
#define RFM22_xtal_osc_por_ctrl_clkhyst 0x10 // Clock Hysteresis Setting.
|
||||
#define RFM22_xtal_osc_por_ctrl_enbias2x 0x08 // 2 Times Higher Bias Current Enable.
|
||||
#define RFM22_xtal_osc_por_ctrl_enamp2x 0x04 // 2 Times Higher Amplification Enable.
|
||||
#define RFM22_xtal_osc_por_ctrl_bufovr 0x02 // Output Buffer Enable Override.
|
||||
#define RFM22_xtal_osc_por_ctrl_enbuf 0x01 // Output Buffer Enable.
|
||||
/*
|
||||
#define RFM22_rc_osc_coarse_calbration_override 0x63 // R/W
|
||||
#define RFM22_rc_osc_fine_calbration_override 0x64 // R/W
|
||||
|
||||
#define RFM22_ldo_control_override 0x65 // R/W
|
||||
#define RFM22_ldo_level_setting 0x66 // R/W
|
||||
|
||||
#define RFM22_deltasigma_adc_tuning1 0x67 // R/W
|
||||
#define RFM22_deltasigma_adc_tuning2 0x68 // R/W
|
||||
*/
|
||||
#define RFM22_agc_override1 0x69 // R/W
|
||||
#define RFM22_agc_ovr1_sgi 0x40 // AGC Loop, Set Gain Increase. If set to 0 then gain increasing will not be allowed. If set to 1 then gain increasing is allowed, default is 0.
|
||||
#define RFM22_agc_ovr1_agcen 0x20 // Automatic Gain Control Enable. When this bit is set then the result of the control can be read out from bits [4:0], otherwise the gain can be controlled manually by writing into bits [4:0].
|
||||
#define RFM22_agc_ovr1_lnagain 0x10 // LNA Gain Select. 0 = min gain = 5dB, 1 = max gain = 25 dB.
|
||||
#define RFM22_agc_ovr1_pga_mask 0x0F // PGA Gain Override Value.
|
||||
|
||||
//#define RFM22_agc_override2 0x6A // R/W
|
||||
|
||||
//#define RFM22_gfsk_fir_coeff_addr 0x6B // R/W
|
||||
//#define RFM22_gfsk_fir_coeff_value 0x6C // R/W
|
||||
|
||||
#define RFM22_tx_power 0x6D // R/W
|
||||
#define RFM22_tx_pwr_txpow_0 0x00 // +1dBm .. 1.25mW
|
||||
#define RFM22_tx_pwr_txpow_1 0x01 // +2dBm .. 1.6mW
|
||||
#define RFM22_tx_pwr_txpow_2 0x02 // +5dBm .. 3.16mW
|
||||
#define RFM22_tx_pwr_txpow_3 0x03 // +8dBm .. 6.3mW
|
||||
#define RFM22_tx_pwr_txpow_4 0x04 // +11dBm .. 12.6mW
|
||||
#define RFM22_tx_pwr_txpow_5 0x05 // +14dBm .. 25mW
|
||||
#define RFM22_tx_pwr_txpow_6 0x06 // +17dBm .. 50mW
|
||||
#define RFM22_tx_pwr_txpow_7 0x07 // +20dBm .. 100mW
|
||||
#define RFM22_tx_pwr_lna_sw 0x08 // LNA Switch Controller. If set, lna_sw control from the digital will go high during TX modes, and low during other times. If reset, the digital control signal is low at all times.
|
||||
#define RFM22_tx_pwr_papeaklvl_0 0x10 // " "
|
||||
#define RFM22_tx_pwr_papeaklvl_1 0x20 // PA Peak Detect Level (direct from register). 00 = 6.5, 01 = 7, 10 = 7.5, 11 = 8, 00 = default
|
||||
#define RFM22_tx_pwr_papeaken 0x40 // PA Peak Detector Enable.
|
||||
#define RFM22_tx_pwr_papeakval 0x80 // PA Peak Detector Value Read Register. Reading a 1 in this register when the papeaken=1 then the PA drain voltage is too high and the match network needs adjusting for optimal efficiency.
|
||||
|
||||
#define RFM22_tx_data_rate1 0x6E // R/W
|
||||
#define RFM22_tx_data_rate0 0x6F // R/W
|
||||
|
||||
#define RFM22_modulation_mode_control1 0x70 // R/W
|
||||
#define RFM22_mmc1_enwhite 0x01 // Data Whitening is Enabled if this bit is set.
|
||||
#define RFM22_mmc1_enmanch 0x02 // Manchester Coding is Enabled if this bit is set.
|
||||
#define RFM22_mmc1_enmaninv 0x04 // Manchester Data Inversion is Enabled if this bit is set.
|
||||
#define RFM22_mmc1_manppol 0x08 // Manchester Preamble Polarity (will transmit a series of 1 if set, or series of 0 if reset).
|
||||
#define RFM22_mmc1_enphpwdn 0x10 // If set, the Packet Handler will be powered down when chip is in low power mode.
|
||||
#define RFM22_mmc1_txdtrtscale 0x20 // This bit should be set for Data Rates below 30 kbps.
|
||||
|
||||
#define RFM22_modulation_mode_control2 0x71 // R/W
|
||||
#define RFM22_mmc2_modtyp_mask 0x03 // Modulation type.
|
||||
#define RFM22_mmc2_modtyp_none 0x00 //
|
||||
#define RFM22_mmc2_modtyp_ook 0x01 //
|
||||
#define RFM22_mmc2_modtyp_fsk 0x02 //
|
||||
#define RFM22_mmc2_modtyp_gfsk 0x03 //
|
||||
#define RFM22_mmc2_fd 0x04 // MSB of Frequency Deviation Setting, see "Register 72h. Frequency Deviation".
|
||||
#define RFM22_mmc2_eninv 0x08 // Invert TX and RX Data.
|
||||
#define RFM22_mmc2_dtmod_mask 0x30 // Modulation source.
|
||||
#define RFM22_mmc2_dtmod_dm_gpio 0x00 //
|
||||
#define RFM22_mmc2_dtmod_dm_sdi 0x10 //
|
||||
#define RFM22_mmc2_dtmod_fifo 0x20 //
|
||||
#define RFM22_mmc2_dtmod_pn9 0x30 //
|
||||
#define RFM22_mmc2_trclk_mask 0xC0 // TX Data Clock Configuration.
|
||||
#define RFM22_mmc2_trclk_clk_none 0x00 //
|
||||
#define RFM22_mmc2_trclk_clk_gpio 0x40 //
|
||||
#define RFM22_mmc2_trclk_clk_sdo 0x80 //
|
||||
#define RFM22_mmc2_trclk_clk_nirq 0xC0 //
|
||||
|
||||
#define RFM22_frequency_deviation 0x72 // R/W
|
||||
|
||||
#define RFM22_frequency_offset1 0x73 // R/W
|
||||
#define RFM22_frequency_offset2 0x74 // R/W
|
||||
|
||||
#define RFM22_frequency_band_select 0x75 // R/W
|
||||
#define RFM22_fb_mask 0x1F
|
||||
#define RFM22_fbs_hbsel 0x20
|
||||
#define RFM22_fbs_sbse 0x40
|
||||
|
||||
#define RFM22_nominal_carrier_frequency1 0x76 // R/W
|
||||
#define RFM22_nominal_carrier_frequency0 0x77 // R/W
|
||||
|
||||
#define RFM22_frequency_hopping_channel_select 0x79 // R/W
|
||||
#define RFM22_frequency_hopping_step_size 0x7A // R/W
|
||||
|
||||
#define RFM22_tx_fifo_control1 0x7C // R/W .. TX FIFO Almost Full Threshold (0 - 63)
|
||||
#define RFM22_tx_fifo_control1_mask 0x3F
|
||||
|
||||
#define RFM22_tx_fifo_control2 0x7D // R/W .. TX FIFO Almost Empty Threshold (0 - 63)
|
||||
#define RFM22_tx_fifo_control2_mask 0x3F
|
||||
|
||||
#define RFM22_rx_fifo_control 0x7E // R/W .. RX FIFO Almost Full Threshold (0 - 63)
|
||||
#define RFM22_rx_fifo_control_mask 0x3F
|
||||
|
||||
#define RFM22_fifo_access 0x7F // R/W
|
||||
|
||||
// ************************************
|
||||
|
||||
typedef int16_t ( *t_rfm22_TxDataByteCallback ) (void);
|
||||
typedef bool ( *t_rfm22_RxDataCallback ) (void *data, uint8_t len);
|
||||
|
||||
// ************************************
|
||||
|
||||
uint32_t rfm22_minFrequency(void);
|
||||
uint32_t rfm22_maxFrequency(void);
|
||||
|
||||
void rfm22_setNominalCarrierFrequency(uint32_t frequency_hz);
|
||||
uint32_t rfm22_getNominalCarrierFrequency(void);
|
||||
|
||||
float rfm22_getFrequencyStepSize(void);
|
||||
|
||||
void rfm22_setFreqHopChannel(uint8_t channel);
|
||||
uint8_t rfm22_freqHopChannel(void);
|
||||
|
||||
uint32_t rfm22_freqHopSize(void);
|
||||
|
||||
void rfm22_setDatarate(uint32_t datarate_bps, bool data_whitening);
|
||||
uint32_t rfm22_getDatarate(void);
|
||||
|
||||
void rfm22_setRxMode(uint8_t mode, bool multi_packet_mode);
|
||||
|
||||
int8_t rfm22_getRSSI(void);
|
||||
|
||||
int8_t rfm22_receivedRSSI(void);
|
||||
int32_t rfm22_receivedAFCHz(void);
|
||||
uint16_t rfm22_receivedLength(void);
|
||||
uint8_t * rfm22_receivedPointer(void);
|
||||
void rfm22_receivedDone(void);
|
||||
|
||||
int32_t rfm22_sendData(void *data, uint16_t length, bool send_immediately);
|
||||
|
||||
void rfm22_setFreqCalibration(uint8_t value);
|
||||
uint8_t rfm22_getFreqCalibration(void);
|
||||
|
||||
void rfm22_setTxPower(uint8_t tx_pwr);
|
||||
uint8_t rfm22_getTxPower(void);
|
||||
|
||||
void rfm22_setTxStream(void); // TEST ONLY
|
||||
|
||||
void rfm22_setTxNormal(void);
|
||||
void rfm22_setTxCarrierMode(void);
|
||||
void rfm22_setTxPNMode(void);
|
||||
|
||||
int8_t rfm22_currentMode(void);
|
||||
bool rfm22_transmitting(void);
|
||||
|
||||
bool rfm22_channelIsClear(void);
|
||||
|
||||
bool rfm22_txReady(void);
|
||||
|
||||
void rfm22_1ms_tick(void);
|
||||
|
||||
void rfm22_TxDataByte_SetCallback(t_rfm22_TxDataByteCallback new_function);
|
||||
void rfm22_RxData_SetCallback(t_rfm22_RxDataCallback new_function);
|
||||
|
||||
int rfm22_init_scan_spectrum(uint32_t min_frequency_hz, uint32_t max_frequency_hz);
|
||||
int rfm22_init_tx_stream(uint32_t min_frequency_hz, uint32_t max_frequency_hz);
|
||||
int rfm22_init_rx_stream(uint32_t min_frequency_hz, uint32_t max_frequency_hz);
|
||||
int rfm22_init_normal(uint32_t id, uint32_t min_frequency_hz, uint32_t max_frequency_hz, uint32_t freq_hop_step_size);
|
||||
|
||||
#endif /* PIOS_RFM22B_PRIV_H */
|
||||
|
||||
/**
|
||||
* @}
|
||||
* @}
|
||||
*/
|
@ -1,24 +1,24 @@
|
||||
#####
|
||||
# Project: OpenPilot Pip Modems
|
||||
#
|
||||
#
|
||||
# Makefile for OpenPilot Pip Modem project
|
||||
# Project: OpenPilot
|
||||
#
|
||||
#
|
||||
# Makefile for OpenPilot project build PiOS and the AP.
|
||||
#
|
||||
# The OpenPilot Team, http://www.openpilot.org, Copyright (C) 2009.
|
||||
#
|
||||
#
|
||||
#
|
||||
# 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
|
||||
# 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
|
||||
#
|
||||
# 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.,
|
||||
#
|
||||
# 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
|
||||
#####
|
||||
|
||||
@ -33,12 +33,29 @@ TARGET := fw_$(BOARD_NAME)
|
||||
# Directory for output files (lst, obj, dep, elf, sym, map, hex, bin etc.)
|
||||
OUTDIR := $(TOP)/build/$(TARGET)
|
||||
|
||||
# Debugging (YES/NO) ?
|
||||
# Set developer code and compile options
|
||||
# Set to YES to compile for debugging
|
||||
DEBUG ?= NO
|
||||
|
||||
# Use Code Sourcery toolchain (YES/NO) ?
|
||||
# Include objects that are just nice information to show
|
||||
DIAGNOSTICS ?= NO
|
||||
|
||||
# Set to YES to build a FW version that will erase all flash memory
|
||||
ERASE_FLASH ?= NO
|
||||
# Set to YES to use the Servo output pins for debugging via scope or logic analyser
|
||||
ENABLE_DEBUG_PINS ?= NO
|
||||
|
||||
# Set to Yes to enable the AUX UART which is mapped on the S1 (Tx) and S2 (Rx) servo outputs
|
||||
ENABLE_AUX_UART ?= NO
|
||||
|
||||
USE_GPS ?= NO
|
||||
|
||||
USE_I2C ?= YES
|
||||
|
||||
# Set to YES when using Code Sourcery toolchain
|
||||
CODE_SOURCERY ?= YES
|
||||
|
||||
# Remove command is different for Code Sourcery on Windows
|
||||
ifeq ($(CODE_SOURCERY), YES)
|
||||
REMOVE_CMD = cs-rm
|
||||
else
|
||||
@ -47,56 +64,85 @@ endif
|
||||
|
||||
FLASH_TOOL = OPENOCD
|
||||
|
||||
# Include the USB files (YES/NO) ?
|
||||
USE_USB = YES
|
||||
# List of modules to include
|
||||
OPTMODULES =
|
||||
MODULES = RadioComBridge
|
||||
|
||||
# Paths
|
||||
HOME_DIR = ./
|
||||
HOME_DIR_INC = $(HOME_DIR)/inc
|
||||
PIOS = ../PiOS
|
||||
PIOSINC = $(PIOS)/inc
|
||||
OPSYSTEM = ./System
|
||||
OPSYSTEMINC = $(OPSYSTEM)/inc
|
||||
OPUAVTALK = ../UAVTalk
|
||||
OPUAVTALKINC = $(OPUAVTALK)/inc
|
||||
OPUAVOBJ = ../UAVObjects
|
||||
OPUAVOBJINC = $(OPUAVOBJ)/inc
|
||||
OPTESTS = ./Tests
|
||||
OPMODULEDIR = ../Modules
|
||||
FLIGHTLIB = ../Libraries
|
||||
FLIGHTLIBINC = $(FLIGHTLIB)/inc
|
||||
RSCODEINC = $(FLIGHTLIB)/rscode
|
||||
PIOS = ../PiOS
|
||||
PIOSINC = $(PIOS)/inc
|
||||
PIOSSTM32F10X = $(PIOS)/STM32F10x
|
||||
PIOSCOMMON = $(PIOS)/Common
|
||||
PIOSBOARDS = $(PIOS)/Boards
|
||||
APPLIBDIR = $(PIOSSTM32F10X)/Libraries
|
||||
STMLIBDIR = $(APPLIBDIR)
|
||||
STMSPDDIR = $(STMLIBDIR)/STM32F10x_StdPeriph_Driver
|
||||
ifeq ($(USE_USB), YES)
|
||||
STMUSBDIR = $(STMLIBDIR)/STM32_USB-FS-Device_Driver
|
||||
endif
|
||||
STMUSBDIR = $(STMLIBDIR)/STM32_USB-FS-Device_Driver
|
||||
STMSPDSRCDIR = $(STMSPDDIR)/src
|
||||
STMSPDINCDIR = $(STMSPDDIR)/inc
|
||||
ifeq ($(USE_USB), YES)
|
||||
STMUSBSRCDIR = $(STMUSBDIR)/src
|
||||
STMUSBINCDIR = $(STMUSBDIR)/inc
|
||||
endif
|
||||
STMUSBSRCDIR = $(STMUSBDIR)/src
|
||||
STMUSBINCDIR = $(STMUSBDIR)/inc
|
||||
CMSISDIR = $(STMLIBDIR)/CMSIS/Core/CM3
|
||||
BOOT = ../Bootloaders/AHRS
|
||||
BOOTINC = $(BOOT)/inc
|
||||
DOSFSDIR = $(APPLIBDIR)/dosfs
|
||||
MSDDIR = $(APPLIBDIR)/msd
|
||||
RTOSDIR = $(APPLIBDIR)/FreeRTOS
|
||||
RTOSSRCDIR = $(RTOSDIR)/Source
|
||||
RTOSINCDIR = $(RTOSSRCDIR)/include
|
||||
DOXYGENDIR = ../Doc/Doxygen
|
||||
AHRSBOOTLOADER = ../Bootloaders/AHRS/
|
||||
AHRSBOOTLOADERINC = $(AHRSBOOTLOADER)/inc
|
||||
PYMITE = $(FLIGHTLIB)/PyMite
|
||||
PYMITELIB = $(PYMITE)/lib
|
||||
PYMITEPLAT = $(PYMITE)/platform/openpilot
|
||||
PYMITETOOLS = $(PYMITE)/tools
|
||||
PYMITEVM = $(PYMITE)/vm
|
||||
PYMITEINC = $(PYMITEVM)
|
||||
PYMITEINC += $(PYMITEPLAT)
|
||||
PYMITEINC += $(OUTDIR)
|
||||
FLIGHTPLANLIB = $(OPMODULEDIR)/FlightPlan/lib
|
||||
FLIGHTPLANS = $(OPMODULEDIR)/FlightPlan/flightplans
|
||||
HWDEFSINC = ../board_hw_defs/$(BOARD_NAME)
|
||||
|
||||
OPUAVSYNTHDIR = $(OUTDIR)/../uavobject-synthetics/flight
|
||||
|
||||
# List C source files here. (C dependencies are automatically generated.)
|
||||
# use file-extension c for "c-only"-files
|
||||
|
||||
## Core:
|
||||
SRC += $(HOME_DIR)/main.c
|
||||
SRC += $(HOME_DIR)/pios_board.c
|
||||
SRC += $(HOME_DIR)/crc.c
|
||||
SRC += $(HOME_DIR)/aes.c
|
||||
SRC += $(HOME_DIR)/rfm22b.c
|
||||
SRC += $(HOME_DIR)/packet_handler.c
|
||||
SRC += $(HOME_DIR)/stream.c
|
||||
SRC += $(HOME_DIR)/ppm.c
|
||||
SRC += $(HOME_DIR)/transparent_comms.c
|
||||
#SRC += $(HOME_DIR)/api_comms.c
|
||||
SRC += $(HOME_DIR)/api_config.c
|
||||
SRC += $(HOME_DIR)/saved_settings.c
|
||||
SRC += $(HOME_DIR)/gpio_in.c
|
||||
SRC += $(HOME_DIR)/stopwatch.c
|
||||
SRC += $(HOME_DIR)/watchdog.c
|
||||
SRC += $(FLIGHTLIB)/fifo_buffer.c
|
||||
ifndef TESTAPP
|
||||
## MODULES
|
||||
SRC += ${foreach MOD, ${MODULES}, ${wildcard ${OPMODULEDIR}/${MOD}/*.c}}
|
||||
## OPENPILOT CORE:
|
||||
SRC += ${OPMODULEDIR}/PipXtreme/pipxtrememod.c
|
||||
SRC += $(OPSYSTEM)/pipxtreme.c
|
||||
SRC += $(OPSYSTEM)/pios_board.c
|
||||
SRC += $(OPUAVTALK)/uavtalk.c
|
||||
SRC += $(OPUAVOBJ)/uavobjectmanager.c
|
||||
SRC += $(OPUAVOBJ)/eventdispatcher.c
|
||||
else
|
||||
## TESTCODE
|
||||
SRC += $(OPTESTS)/test_common.c
|
||||
SRC += $(OPTESTS)/$(TESTAPP).c
|
||||
endif
|
||||
|
||||
## UAVOBJECTS
|
||||
ifndef TESTAPP
|
||||
SRC += $(OPUAVSYNTHDIR)/gcsreceiver.c
|
||||
SRC += $(OPUAVSYNTHDIR)/pipxstatus.c
|
||||
SRC += $(OPUAVSYNTHDIR)/pipxsettings.c
|
||||
SRC += $(OPUAVSYNTHDIR)/objectpersistence.c
|
||||
|
||||
endif
|
||||
|
||||
## PIOS Hardware (STM32F10x)
|
||||
SRC += $(PIOSSTM32F10X)/pios_sys.c
|
||||
@ -104,42 +150,60 @@ SRC += $(PIOSSTM32F10X)/pios_led.c
|
||||
SRC += $(PIOSSTM32F10X)/pios_delay.c
|
||||
SRC += $(PIOSSTM32F10X)/pios_usart.c
|
||||
SRC += $(PIOSSTM32F10X)/pios_irq.c
|
||||
SRC += $(PIOSSTM32F10X)/pios_adc.c
|
||||
SRC += $(PIOSSTM32F10X)/pios_gpio.c
|
||||
SRC += $(PIOSSTM32F10X)/pios_spi.c
|
||||
SRC += $(PIOSSTM32F10X)/pios_ppm.c
|
||||
SRC += $(PIOSSTM32F10X)/pios_debug.c
|
||||
SRC += $(PIOSSTM32F10X)/pios_gpio.c
|
||||
SRC += $(PIOSSTM32F10X)/pios_exti.c
|
||||
SRC += $(PIOSSTM32F10X)/pios_rtc.c
|
||||
SRC += $(PIOSSTM32F10X)/pios_wdg.c
|
||||
SRC += $(PIOSSTM32F10X)/pios_tim.c
|
||||
SRC += $(PIOSSTM32F10X)/pios_pwm.c
|
||||
SRC += $(PIOSSTM32F10X)/pios_eeprom.c
|
||||
SRC += $(PIOSSTM32F10X)/pios_bl_helper.c
|
||||
|
||||
# PIOS USB related files (seperated to make code maintenance more easy)
|
||||
ifeq ($(USE_USB), YES)
|
||||
SRC += $(PIOSSTM32F10X)/pios_usb.c
|
||||
SRC += $(PIOSSTM32F10X)/pios_usbhook.c
|
||||
SRC += $(PIOSSTM32F10X)/pios_usb_hid.c
|
||||
SRC += $(PIOSSTM32F10X)/pios_usb_hid_istr.c
|
||||
SRC += $(PIOSSTM32F10X)/pios_usb_hid_pwr.c
|
||||
SRC += $(HOME_DIR)/pios_usb_board_data.c
|
||||
SRC += $(PIOSCOMMON)/pios_usb_desc_hid_only.c
|
||||
SRC += $(PIOSCOMMON)/pios_usb_util.c
|
||||
endif
|
||||
SRC += $(PIOSSTM32F10X)/pios_usb.c
|
||||
SRC += $(PIOSSTM32F10X)/pios_usbhook.c
|
||||
SRC += $(PIOSSTM32F10X)/pios_usb_hid.c
|
||||
SRC += $(PIOSSTM32F10X)/pios_usb_cdc.c
|
||||
SRC += $(PIOSSTM32F10X)/pios_usb_hid_istr.c
|
||||
SRC += $(PIOSSTM32F10X)/pios_usb_hid_pwr.c
|
||||
SRC += $(OPSYSTEM)/pios_usb_board_data.c
|
||||
SRC += $(PIOSCOMMON)/pios_usb_desc_hid_cdc.c
|
||||
SRC += $(PIOSCOMMON)/pios_usb_desc_hid_only.c
|
||||
SRC += $(PIOSCOMMON)/pios_usb_util.c
|
||||
|
||||
## PIOS Hardware (Common)
|
||||
SRC += $(PIOSCOMMON)/pios_crc.c
|
||||
SRC += $(PIOSCOMMON)/pios_com.c
|
||||
SRC += $(PIOSCOMMON)/pios_i2c_esc.c
|
||||
SRC += $(PIOSCOMMON)/pios_rcvr.c
|
||||
SRC += $(PIOSCOMMON)/printf-stdarg.c
|
||||
SRC += $(PIOSCOMMON)/pios_rfm22b.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
|
||||
SRC += $(FLIGHTLIB)/rscode/galois.c
|
||||
|
||||
## CMSIS for STM32
|
||||
SRC += $(CMSISDIR)/core_cm3.c
|
||||
SRC += $(CMSISDIR)/system_stm32f10x.c
|
||||
|
||||
## Used parts of the STM-Library
|
||||
SRC += $(STMSPDSRCDIR)/stm32f10x_adc.c
|
||||
SRC += $(STMSPDSRCDIR)/stm32f10x_bkp.c
|
||||
SRC += $(STMSPDSRCDIR)/stm32f10x_crc.c
|
||||
SRC += $(STMSPDSRCDIR)/stm32f10x_dac.c
|
||||
SRC += $(STMSPDSRCDIR)/stm32f10x_dbgmcu.c
|
||||
SRC += $(STMSPDSRCDIR)/stm32f10x_dma.c
|
||||
SRC += $(STMSPDSRCDIR)/stm32f10x_exti.c
|
||||
SRC += $(STMSPDSRCDIR)/stm32f10x_flash.c
|
||||
SRC += $(STMSPDSRCDIR)/stm32f10x_gpio.c
|
||||
SRC += $(STMSPDSRCDIR)/stm32f10x_iwdg.c
|
||||
SRC += $(STMSPDSRCDIR)/stm32f10x_i2c.c
|
||||
SRC += $(STMSPDSRCDIR)/stm32f10x_pwr.c
|
||||
SRC += $(STMSPDSRCDIR)/stm32f10x_rcc.c
|
||||
@ -147,31 +211,40 @@ SRC += $(STMSPDSRCDIR)/stm32f10x_rtc.c
|
||||
SRC += $(STMSPDSRCDIR)/stm32f10x_spi.c
|
||||
SRC += $(STMSPDSRCDIR)/stm32f10x_tim.c
|
||||
SRC += $(STMSPDSRCDIR)/stm32f10x_usart.c
|
||||
SRC += $(STMSPDSRCDIR)/stm32f10x_iwdg.c
|
||||
SRC += $(STMSPDSRCDIR)/stm32f10x_dbgmcu.c
|
||||
SRC += $(STMSPDSRCDIR)/misc.c
|
||||
|
||||
## STM32 USB Library
|
||||
ifeq ($(USE_USB), YES)
|
||||
SRC += $(STMUSBSRCDIR)/usb_core.c
|
||||
SRC += $(STMUSBSRCDIR)/usb_init.c
|
||||
SRC += $(STMUSBSRCDIR)/usb_int.c
|
||||
SRC += $(STMUSBSRCDIR)/usb_mem.c
|
||||
SRC += $(STMUSBSRCDIR)/usb_regs.c
|
||||
SRC += $(STMUSBSRCDIR)/usb_sil.c
|
||||
endif
|
||||
SRC += $(STMUSBSRCDIR)/usb_core.c
|
||||
SRC += $(STMUSBSRCDIR)/usb_init.c
|
||||
SRC += $(STMUSBSRCDIR)/usb_int.c
|
||||
SRC += $(STMUSBSRCDIR)/usb_mem.c
|
||||
SRC += $(STMUSBSRCDIR)/usb_regs.c
|
||||
SRC += $(STMUSBSRCDIR)/usb_sil.c
|
||||
|
||||
## RTOS
|
||||
SRC += $(RTOSSRCDIR)/list.c
|
||||
SRC += $(RTOSSRCDIR)/queue.c
|
||||
SRC += $(RTOSSRCDIR)/tasks.c
|
||||
|
||||
## RTOS Portable
|
||||
SRC += $(RTOSSRCDIR)/portable/GCC/ARM_CM3/port.c
|
||||
SRC += $(RTOSSRCDIR)/portable/MemMang/heap_1.c
|
||||
|
||||
# List C source files here which must be compiled in ARM-Mode (no -mthumb).
|
||||
# use file-extension c for "c-only"-files
|
||||
## just for testing, timer.c could be compiled in thumb-mode too
|
||||
SRCARM =
|
||||
SRCARM =
|
||||
|
||||
# List C++ source files here.
|
||||
# use file-extension .cpp for C++-files (not .C)
|
||||
CPPSRC =
|
||||
CPPSRC =
|
||||
|
||||
# List C++ source files here which must be compiled in ARM-Mode.
|
||||
# use file-extension .cpp for C++-files (not .C)
|
||||
#CPPSRCARM = $(TARGET).cpp
|
||||
CPPSRCARM =
|
||||
CPPSRCARM =
|
||||
|
||||
# List Assembler source files here.
|
||||
# Make them always end in a capital .S. Files ending in a lowercase .s
|
||||
@ -183,35 +256,48 @@ CPPSRCARM =
|
||||
ASRC = $(PIOSSTM32F10X)/startup_stm32f10x_$(MODEL)$(MODEL_SUFFIX).S
|
||||
|
||||
# List Assembler source files here which must be assembled in ARM-Mode..
|
||||
ASRCARM =
|
||||
ASRCARM =
|
||||
|
||||
# List any extra directories to look for include files here.
|
||||
# Each directory must be seperated by a space.
|
||||
EXTRAINCDIRS += $(HOME_DIR)
|
||||
EXTRAINCDIRS += $(HOME_DIR_INC)
|
||||
EXTRAINCDIRS = $(OPSYSTEM)
|
||||
EXTRAINCDIRS += $(OPSYSTEMINC)
|
||||
EXTRAINCDIRS += $(OPUAVTALK)
|
||||
EXTRAINCDIRS += $(OPUAVTALKINC)
|
||||
EXTRAINCDIRS += $(OPUAVOBJ)
|
||||
EXTRAINCDIRS += $(OPUAVOBJINC)
|
||||
EXTRAINCDIRS += $(OPUAVSYNTHDIR)
|
||||
EXTRAINCDIRS += $(PIOS)
|
||||
EXTRAINCDIRS += $(PIOSINC)
|
||||
EXTRAINCDIRS += $(FLIGHTLIBINC)
|
||||
EXTRAINCDIRS += $(RSCODEINC)
|
||||
EXTRAINCDIRS += $(PIOSSTM32F10X)
|
||||
EXTRAINCDIRS += $(PIOSCOMMON)
|
||||
EXTRAINCDIRS += $(PIOSBOARDS)
|
||||
EXTRAINCDIRS += $(STMSPDINCDIR)
|
||||
ifeq ($(USE_USB), YES)
|
||||
EXTRAINCDIRS += $(STMUSBINCDIR)
|
||||
endif
|
||||
EXTRAINCDIRS += $(STMUSBINCDIR)
|
||||
EXTRAINCDIRS += $(CMSISDIR)
|
||||
EXTRAINCDIRS += $(BOOTINC)
|
||||
EXTRAINCDIRS += $(DOSFSDIR)
|
||||
EXTRAINCDIRS += $(MSDDIR)
|
||||
EXTRAINCDIRS += $(RTOSINCDIR)
|
||||
EXTRAINCDIRS += $(APPLIBDIR)
|
||||
EXTRAINCDIRS += $(RTOSSRCDIR)/portable/GCC/ARM_CM3
|
||||
EXTRAINCDIRS += $(AHRSBOOTLOADERINC)
|
||||
EXTRAINCDIRS += $(PYMITEINC)
|
||||
EXTRAINCDIRS += $(HWDEFSINC)
|
||||
|
||||
EXTRAINCDIRS += ${foreach MOD, ${OPTMODULES} ${MODULES}, ${OPMODULEDIR}/${MOD}/inc} ${OPMODULEDIR}/System/inc
|
||||
|
||||
|
||||
# List any extra directories to look for library files here.
|
||||
# Also add directories where the linker should search for
|
||||
# includes from linker-script to the list
|
||||
# Each directory must be seperated by a space.
|
||||
EXTRA_LIBDIRS =
|
||||
EXTRA_LIBDIRS =
|
||||
|
||||
# Extra Libraries
|
||||
# Each library-name must be seperated by a space.
|
||||
# i.e. to link with libxyz.a, libabc.a and libefsl.a:
|
||||
# i.e. to link with libxyz.a, libabc.a and libefsl.a:
|
||||
# EXTRA_LIBS = xyz abc efsl
|
||||
# for newlib-lpc (file: libnewlibc-lpc.a):
|
||||
# EXTRA_LIBS = newlib-lpc
|
||||
@ -220,19 +306,18 @@ EXTRA_LIBS =
|
||||
# Path to Linker-Scripts
|
||||
LINKERSCRIPTPATH = $(PIOSSTM32F10X)
|
||||
|
||||
# Optimization level, can be [0, 1, 2, 3, s].
|
||||
# Optimization level, can be [0, 1, 2, 3, s].
|
||||
# 0 = turn off optimization. s = optimize for size.
|
||||
# (Note: 3 is not always the best optimization level. See avr-libc FAQ.)
|
||||
|
||||
ifeq ($(DEBUG),YES)
|
||||
OPT = 0
|
||||
OPT = 1
|
||||
else
|
||||
OPT = s
|
||||
#OPT = 2
|
||||
endif
|
||||
|
||||
# Output format. (can be ihex or binary or both)
|
||||
# binary to create a load-image in raw-binary format i.e. for SAM-BA,
|
||||
# binary to create a load-image in raw-binary format i.e. for SAM-BA,
|
||||
# ihex to create a load-image in Intel hex format
|
||||
#LOADFORMAT = ihex
|
||||
#LOADFORMAT = binary
|
||||
@ -241,13 +326,30 @@ LOADFORMAT = both
|
||||
# Debugging format.
|
||||
DEBUGF = dwarf-2
|
||||
|
||||
# Place project-specific -D (define) and/or
|
||||
# Place project-specific -D (define) and/or
|
||||
# -U options for C here.
|
||||
CDEFS = -DSTM32F10X_$(MODEL)
|
||||
CDEFS += -DUSE_STDPERIPH_DRIVER
|
||||
CDEFS += -DUSE_$(BOARD)
|
||||
ifeq ($(ENABLE_DEBUG_PINS), YES)
|
||||
CDEFS += -DPIOS_ENABLE_DEBUG_PINS
|
||||
endif
|
||||
ifeq ($(ENABLE_AUX_UART), YES)
|
||||
CDEFS += -DPIOS_ENABLE_AUX_UART
|
||||
endif
|
||||
ifeq ($(ERASE_FLASH), YES)
|
||||
CDEFS += -DERASE_FLASH
|
||||
endif
|
||||
|
||||
# Place project-specific -D and/or -U options for
|
||||
ifneq ($(USE_GPS), NO)
|
||||
CDEFS += -DUSE_GPS
|
||||
endif
|
||||
|
||||
ifeq ($(USE_I2C), YES)
|
||||
CDEFS += -DUSE_I2C
|
||||
endif
|
||||
|
||||
# Place project-specific -D and/or -U options for
|
||||
# Assembler with preprocessor here.
|
||||
#ADEFS = -DUSE_IRQ_ASM_WRAPPER
|
||||
ADEFS = -D__ASSEMBLY__
|
||||
@ -273,18 +375,27 @@ CSTANDARD = -std=gnu99
|
||||
# Flags for C and C++ (arm-elf-gcc/arm-elf-g++)
|
||||
|
||||
ifeq ($(DEBUG),YES)
|
||||
CFLAGS = -g$(DEBUGF)
|
||||
CFLAGS = -DDEBUG
|
||||
endif
|
||||
|
||||
CFLAGS += -O$(OPT)
|
||||
ifeq ($(DEBUG),NO)
|
||||
CFLAGS += -fdata-sections -ffunction-sections
|
||||
ifeq ($(DIAGNOSTICS),YES)
|
||||
CFLAGS = -DDIAGNOSTICS
|
||||
endif
|
||||
|
||||
CFLAGS += -g$(DEBUGF)
|
||||
CFLAGS += -O$(OPT)
|
||||
CFLAGS += -mcpu=$(MCU)
|
||||
CFLAGS += $(CDEFS)
|
||||
CFLAGS += $(patsubst %,-I%,$(EXTRAINCDIRS)) -I.
|
||||
|
||||
CFLAGS += -mapcs-frame
|
||||
#CFLAGS += -fno-cprop-registers -fno-defer-pop -fno-guess-branch-probability -fno-section-anchors
|
||||
#CFLAGS += -fno-if-conversion -fno-if-conversion2 -fno-ipa-pure-const -fno-ipa-reference -fno-merge-constants
|
||||
#CFLAGS += -fno-split-wide-types -fno-tree-ccp -fno-tree-ch -fno-tree-copy-prop -fno-tree-copyrename
|
||||
#CFLAGS += -fno-tree-dce -fno-tree-dominator-opts -fno-tree-dse -fno-tree-fre -fno-tree-sink -fno-tree-sra
|
||||
#CFLAGS += -fno-tree-ter
|
||||
#CFLAGS += -g$(DEBUGF) -DDEBUG
|
||||
|
||||
CFLAGS += -mapcs-frame
|
||||
CFLAGS += -fomit-frame-pointer
|
||||
ifeq ($(CODE_SOURCERY), YES)
|
||||
CFLAGS += -fpromote-loop-indices
|
||||
@ -297,7 +408,7 @@ CFLAGS += -Wa,-adhlns=$(addprefix $(OUTDIR)/, $(notdir $(addsuffix .lst, $(basen
|
||||
CFLAGS += -MD -MP -MF $(OUTDIR)/dep/$(@F).d
|
||||
|
||||
# flags only for C
|
||||
#CONLYFLAGS += -Wnested-externs
|
||||
#CONLYFLAGS += -Wnested-externs
|
||||
CONLYFLAGS += $(CSTANDARD)
|
||||
|
||||
# Assembler flags.
|
||||
@ -315,14 +426,11 @@ MATH_LIB = -lm
|
||||
# -Map: create map file
|
||||
# --cref: add cross reference to map file
|
||||
LDFLAGS = -nostartfiles -Wl,-Map=$(OUTDIR)/$(TARGET).map,--cref,--gc-sections
|
||||
ifeq ($(DEBUG),NO)
|
||||
LDFLAGS += -Wl,-static -Wl,-s
|
||||
endif
|
||||
LDFLAGS += $(patsubst %,-L%,$(EXTRA_LIBDIRS))
|
||||
LDFLAGS += -lc
|
||||
LDFLAGS += $(patsubst %,-l%,$(EXTRA_LIBS))
|
||||
LDFLAGS += $(MATH_LIB)
|
||||
LDFLAGS += -lc -lgcc
|
||||
LDFLAGS += -lc -lgcc
|
||||
|
||||
# Set linker-script name depending on selected submodel name
|
||||
LDFLAGS += -T$(LINKERSCRIPTPATH)/link_$(BOARD)_memory.ld
|
||||
@ -330,6 +438,7 @@ LDFLAGS += -T$(LINKERSCRIPTPATH)/link_$(BOARD)_sections.ld
|
||||
|
||||
# Define programs and commands.
|
||||
REMOVE = $(REMOVE_CMD) -f
|
||||
PYTHON = python
|
||||
|
||||
# List of all source files.
|
||||
ALLSRC = $(ASRCARM) $(ASRC) $(SRCARM) $(SRC) $(CPPSRCARM) $(CPPSRC)
|
||||
@ -349,13 +458,13 @@ all: build
|
||||
|
||||
ifeq ($(LOADFORMAT),ihex)
|
||||
build: elf hex lss sym
|
||||
else
|
||||
else
|
||||
ifeq ($(LOADFORMAT),binary)
|
||||
build: elf bin lss sym
|
||||
else
|
||||
else
|
||||
ifeq ($(LOADFORMAT),both)
|
||||
build: elf hex bin lss sym
|
||||
else
|
||||
else
|
||||
$(error "$(MSG_FORMATERROR) $(FORMAT)")
|
||||
endif
|
||||
endif
|
||||
@ -365,22 +474,22 @@ endif
|
||||
$(eval $(call LINK_TEMPLATE, $(OUTDIR)/$(TARGET).elf, $(ALLOBJ)))
|
||||
|
||||
# Assemble: create object files from assembler source files.
|
||||
$(foreach src, $(ASRC), $(eval $(call ASSEMBLE_TEMPLATE, $(src))))
|
||||
$(foreach src, $(ASRC), $(eval $(call ASSEMBLE_TEMPLATE, $(src))))
|
||||
|
||||
# Assemble: create object files from assembler source files. ARM-only
|
||||
$(foreach src, $(ASRCARM), $(eval $(call ASSEMBLE_ARM_TEMPLATE, $(src))))
|
||||
$(foreach src, $(ASRCARM), $(eval $(call ASSEMBLE_ARM_TEMPLATE, $(src))))
|
||||
|
||||
# Compile: create object files from C source files.
|
||||
$(foreach src, $(SRC), $(eval $(call COMPILE_C_TEMPLATE, $(src))))
|
||||
$(foreach src, $(SRC), $(eval $(call COMPILE_C_TEMPLATE, $(src))))
|
||||
|
||||
# Compile: create object files from C source files. ARM-only
|
||||
$(foreach src, $(SRCARM), $(eval $(call COMPILE_C_ARM_TEMPLATE, $(src))))
|
||||
$(foreach src, $(SRCARM), $(eval $(call COMPILE_C_ARM_TEMPLATE, $(src))))
|
||||
|
||||
# Compile: create object files from C++ source files.
|
||||
$(foreach src, $(CPPSRC), $(eval $(call COMPILE_CPP_TEMPLATE, $(src))))
|
||||
$(foreach src, $(CPPSRC), $(eval $(call COMPILE_CPP_TEMPLATE, $(src))))
|
||||
|
||||
# Compile: create object files from C++ source files. ARM-only
|
||||
$(foreach src, $(CPPSRCARM), $(eval $(call COMPILE_CPP_ARM_TEMPLATE, $(src))))
|
||||
$(foreach src, $(CPPSRCARM), $(eval $(call COMPILE_CPP_ARM_TEMPLATE, $(src))))
|
||||
|
||||
# Compile: create assembler files from C source files. ARM/Thumb
|
||||
$(eval $(call PARTIAL_COMPILE_TEMPLATE, SRC))
|
||||
@ -397,7 +506,7 @@ $(eval $(call JTAG_TEMPLATE,$(OUTDIR)/$(TARGET).bin,$(FW_BANK_BASE),$(FW_BANK_SI
|
||||
|
||||
.PHONY: elf lss sym hex bin bino opfw
|
||||
elf: $(OUTDIR)/$(TARGET).elf
|
||||
lss: $(OUTDIR)/$(TARGET).lss
|
||||
lss: $(OUTDIR)/$(TARGET).lss
|
||||
sym: $(OUTDIR)/$(TARGET).sym
|
||||
hex: $(OUTDIR)/$(TARGET).hex
|
||||
bin: $(OUTDIR)/$(TARGET).bin
|
||||
@ -433,6 +542,8 @@ clean_list :
|
||||
$(V1) $(REMOVE) $(OUTDIR)/$(TARGET).sym
|
||||
$(V1) $(REMOVE) $(OUTDIR)/$(TARGET).lss
|
||||
$(V1) $(REMOVE) $(OUTDIR)/$(TARGET).bin.o
|
||||
$(V1) $(REMOVE) $(wildcard $(OUTDIR)/*.c)
|
||||
$(V1) $(REMOVE) $(wildcard $(OUTDIR)/*.h)
|
||||
$(V1) $(REMOVE) $(ALLOBJ)
|
||||
$(V1) $(REMOVE) $(LSTFILES)
|
||||
$(V1) $(REMOVE) $(DEPFILES)
|
||||
|
214
flight/PipXtreme/System/alarms.c
Executable file
214
flight/PipXtreme/System/alarms.c
Executable file
@ -0,0 +1,214 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup OpenPilotSystem OpenPilot System
|
||||
* @{
|
||||
* @addtogroup OpenPilotLibraries OpenPilot System Libraries
|
||||
* @brief OpenPilot System libraries are available to all OP modules.
|
||||
* @{
|
||||
* @file alarms.c
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @brief Library for setting and clearing system alarms
|
||||
* @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 "alarms.h"
|
||||
|
||||
// Private constants
|
||||
|
||||
// Private types
|
||||
|
||||
// Private variables
|
||||
static xSemaphoreHandle lock;
|
||||
|
||||
// Private functions
|
||||
static int32_t hasSeverity(SystemAlarmsAlarmOptions severity);
|
||||
|
||||
/**
|
||||
* Initialize the alarms library
|
||||
*/
|
||||
int32_t AlarmsInitialize(void)
|
||||
{
|
||||
SystemAlarmsInitialize();
|
||||
|
||||
lock = xSemaphoreCreateRecursiveMutex();
|
||||
//do not change the default states of the alarms, let the init code generated by the uavobjectgenerator handle that
|
||||
//AlarmsClearAll();
|
||||
//AlarmsDefaultAll();
|
||||
return 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* Set an alarm
|
||||
* @param alarm The system alarm to be modified
|
||||
* @param severity The alarm severity
|
||||
* @return 0 if success, -1 if an error
|
||||
*/
|
||||
int32_t AlarmsSet(SystemAlarmsAlarmElem alarm, SystemAlarmsAlarmOptions severity)
|
||||
{
|
||||
SystemAlarmsData alarms;
|
||||
|
||||
// Check that this is a valid alarm
|
||||
if (alarm >= SYSTEMALARMS_ALARM_NUMELEM)
|
||||
{
|
||||
return -1;
|
||||
}
|
||||
|
||||
// Lock
|
||||
xSemaphoreTakeRecursive(lock, portMAX_DELAY);
|
||||
|
||||
// Read alarm and update its severity only if it was changed
|
||||
SystemAlarmsGet(&alarms);
|
||||
if ( alarms.Alarm[alarm] != severity )
|
||||
{
|
||||
alarms.Alarm[alarm] = severity;
|
||||
SystemAlarmsSet(&alarms);
|
||||
}
|
||||
|
||||
// Release lock
|
||||
xSemaphoreGiveRecursive(lock);
|
||||
return 0;
|
||||
|
||||
}
|
||||
|
||||
/**
|
||||
* Get an alarm
|
||||
* @param alarm The system alarm to be read
|
||||
* @return Alarm severity
|
||||
*/
|
||||
SystemAlarmsAlarmOptions AlarmsGet(SystemAlarmsAlarmElem alarm)
|
||||
{
|
||||
SystemAlarmsData alarms;
|
||||
|
||||
// Check that this is a valid alarm
|
||||
if (alarm >= SYSTEMALARMS_ALARM_NUMELEM)
|
||||
{
|
||||
return 0;
|
||||
}
|
||||
|
||||
// Read alarm
|
||||
SystemAlarmsGet(&alarms);
|
||||
return alarms.Alarm[alarm];
|
||||
}
|
||||
|
||||
/**
|
||||
* Set an alarm to it's default value
|
||||
* @param alarm The system alarm to be modified
|
||||
* @return 0 if success, -1 if an error
|
||||
*/
|
||||
int32_t AlarmsDefault(SystemAlarmsAlarmElem alarm)
|
||||
{
|
||||
return AlarmsSet(alarm, SYSTEMALARMS_ALARM_DEFAULT);
|
||||
}
|
||||
|
||||
/**
|
||||
* Default all alarms
|
||||
*/
|
||||
void AlarmsDefaultAll()
|
||||
{
|
||||
uint32_t n;
|
||||
for (n = 0; n < SYSTEMALARMS_ALARM_NUMELEM; ++n)
|
||||
{
|
||||
AlarmsDefault(n);
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Clear an alarm
|
||||
* @param alarm The system alarm to be modified
|
||||
* @return 0 if success, -1 if an error
|
||||
*/
|
||||
int32_t AlarmsClear(SystemAlarmsAlarmElem alarm)
|
||||
{
|
||||
return AlarmsSet(alarm, SYSTEMALARMS_ALARM_OK);
|
||||
}
|
||||
|
||||
/**
|
||||
* Clear all alarms
|
||||
*/
|
||||
void AlarmsClearAll()
|
||||
{
|
||||
uint32_t n;
|
||||
for (n = 0; n < SYSTEMALARMS_ALARM_NUMELEM; ++n)
|
||||
{
|
||||
AlarmsClear(n);
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Check if there are any alarms with the given or higher severity
|
||||
* @return 0 if no alarms are found, 1 if at least one alarm is found
|
||||
*/
|
||||
int32_t AlarmsHasWarnings()
|
||||
{
|
||||
return hasSeverity(SYSTEMALARMS_ALARM_WARNING);
|
||||
}
|
||||
|
||||
/**
|
||||
* Check if there are any alarms with error or higher severity
|
||||
* @return 0 if no alarms are found, 1 if at least one alarm is found
|
||||
*/
|
||||
int32_t AlarmsHasErrors()
|
||||
{
|
||||
return hasSeverity(SYSTEMALARMS_ALARM_ERROR);
|
||||
};
|
||||
|
||||
/**
|
||||
* Check if there are any alarms with critical or higher severity
|
||||
* @return 0 if no alarms are found, 1 if at least one alarm is found
|
||||
*/
|
||||
int32_t AlarmsHasCritical()
|
||||
{
|
||||
return hasSeverity(SYSTEMALARMS_ALARM_CRITICAL);
|
||||
};
|
||||
|
||||
/**
|
||||
* Check if there are any alarms with the given or higher severity
|
||||
* @return 0 if no alarms are found, 1 if at least one alarm is found
|
||||
*/
|
||||
static int32_t hasSeverity(SystemAlarmsAlarmOptions severity)
|
||||
{
|
||||
SystemAlarmsData alarms;
|
||||
uint32_t n;
|
||||
|
||||
// Lock
|
||||
xSemaphoreTakeRecursive(lock, portMAX_DELAY);
|
||||
|
||||
// Read alarms
|
||||
SystemAlarmsGet(&alarms);
|
||||
|
||||
// Go through alarms and check if any are of the given severity or higher
|
||||
for (n = 0; n < SYSTEMALARMS_ALARM_NUMELEM; ++n)
|
||||
{
|
||||
if ( alarms.Alarm[n] >= severity)
|
||||
{
|
||||
xSemaphoreGiveRecursive(lock);
|
||||
return 1;
|
||||
}
|
||||
}
|
||||
|
||||
// If this point is reached then no alarms found
|
||||
xSemaphoreGiveRecursive(lock);
|
||||
return 0;
|
||||
}
|
||||
/**
|
||||
* @}
|
||||
* @}
|
||||
*/
|
||||
|
99
flight/PipXtreme/System/inc/FreeRTOSConfig.h
Executable file
99
flight/PipXtreme/System/inc/FreeRTOSConfig.h
Executable file
@ -0,0 +1,99 @@
|
||||
|
||||
#ifndef FREERTOS_CONFIG_H
|
||||
#define FREERTOS_CONFIG_H
|
||||
|
||||
/*-----------------------------------------------------------
|
||||
* Application specific definitions.
|
||||
*
|
||||
* These definitions should be adjusted for your particular hardware and
|
||||
* application requirements.
|
||||
*
|
||||
* THESE PARAMETERS ARE DESCRIBED WITHIN THE 'CONFIGURATION' SECTION OF THE
|
||||
* FreeRTOS API DOCUMENTATION AVAILABLE ON THE FreeRTOS.org WEB SITE.
|
||||
*
|
||||
* See http://www.freertos.org/a00110.html.
|
||||
*----------------------------------------------------------*/
|
||||
|
||||
/**
|
||||
* @addtogroup PIOS PIOS
|
||||
* @{
|
||||
* @addtogroup FreeRTOS FreeRTOS
|
||||
* @{
|
||||
*/
|
||||
|
||||
/* Notes: We use 5 task priorities */
|
||||
|
||||
#define configUSE_PREEMPTION 1
|
||||
#define configUSE_IDLE_HOOK 1
|
||||
#define configUSE_TICK_HOOK 0
|
||||
#define configUSE_MALLOC_FAILED_HOOK 1
|
||||
#define configCPU_CLOCK_HZ ( ( unsigned long ) 72000000 )
|
||||
#define configTICK_RATE_HZ ( ( portTickType ) 1000 )
|
||||
#define configMAX_PRIORITIES ( ( unsigned portBASE_TYPE ) 5 )
|
||||
#define configMINIMAL_STACK_SIZE ( ( unsigned short ) 48 )
|
||||
#define configTOTAL_HEAP_SIZE ( ( size_t ) ( 54 * 256) )
|
||||
#define configMAX_TASK_NAME_LEN ( 16 )
|
||||
#define configUSE_TRACE_FACILITY 0
|
||||
#define configUSE_16_BIT_TICKS 0
|
||||
#define configIDLE_SHOULD_YIELD 0
|
||||
#define configUSE_MUTEXES 1
|
||||
#define configUSE_RECURSIVE_MUTEXES 1
|
||||
#define configUSE_COUNTING_SEMAPHORES 0
|
||||
#define configUSE_ALTERNATIVE_API 0
|
||||
#define configQUEUE_REGISTRY_SIZE 10
|
||||
|
||||
/* Co-routine definitions. */
|
||||
#define configUSE_CO_ROUTINES 0
|
||||
#define configMAX_CO_ROUTINE_PRIORITIES ( 2 )
|
||||
|
||||
/* Set the following definitions to 1 to include the API function, or zero
|
||||
to exclude the API function. */
|
||||
|
||||
#define INCLUDE_vTaskPrioritySet 1
|
||||
#define INCLUDE_uxTaskPriorityGet 1
|
||||
#define INCLUDE_vTaskDelete 1
|
||||
#define INCLUDE_vTaskCleanUpResources 0
|
||||
#define INCLUDE_vTaskSuspend 1
|
||||
#define INCLUDE_vTaskDelayUntil 1
|
||||
#define INCLUDE_vTaskDelay 1
|
||||
#define INCLUDE_xTaskGetSchedulerState 1
|
||||
#define INCLUDE_xTaskGetCurrentTaskHandle 1
|
||||
#define INCLUDE_uxTaskGetStackHighWaterMark 1
|
||||
|
||||
/* This is the raw value as per the Cortex-M3 NVIC. Values can be 255
|
||||
(lowest) to 1 (highest maskable) to 0 (highest non-maskable). */
|
||||
#define configKERNEL_INTERRUPT_PRIORITY 15 << 4 /* equivalent to NVIC priority 15 */
|
||||
#define configMAX_SYSCALL_INTERRUPT_PRIORITY 3 << 4 /* equivalent to NVIC priority 3 */
|
||||
|
||||
/* This is the value being used as per the ST library which permits 16
|
||||
priority values, 0 to 15. This must correspond to the
|
||||
configKERNEL_INTERRUPT_PRIORITY setting. Here 15 corresponds to the lowest
|
||||
NVIC value of 255. */
|
||||
#define configLIBRARY_KERNEL_INTERRUPT_PRIORITY 15
|
||||
|
||||
#if !defined(ARCH_POSIX) && !defined(ARCH_WIN32)
|
||||
#define CHECK_IRQ_STACK
|
||||
#endif
|
||||
|
||||
/* Enable run time stats collection */
|
||||
#if defined(DIAGNOSTICS)
|
||||
#define configCHECK_FOR_STACK_OVERFLOW 2
|
||||
|
||||
#define configGENERATE_RUN_TIME_STATS 1
|
||||
#define INCLUDE_uxTaskGetRunTime 1
|
||||
#define portCONFIGURE_TIMER_FOR_RUN_TIME_STATS()\
|
||||
do {\
|
||||
(*(unsigned long *)0xe000edfc) |= (1<<24);/* DEMCR |= DEMCR_TRCENA */\
|
||||
(*(unsigned long *)0xe0001000) |= 1; /* DWT_CTRL |= DWT_CYCCNT_ENA */\
|
||||
} while(0)
|
||||
#define portGET_RUN_TIME_COUNTER_VALUE() (*(unsigned long *)0xe0001004)/* DWT_CYCCNT */
|
||||
#else
|
||||
#define configCHECK_FOR_STACK_OVERFLOW 1
|
||||
#endif
|
||||
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
#endif /* FREERTOS_CONFIG_H */
|
40
flight/PipXtreme/inc/ppm.h → flight/PipXtreme/System/inc/alarms.h
Normal file → Executable file
40
flight/PipXtreme/inc/ppm.h → flight/PipXtreme/System/inc/alarms.h
Normal file → Executable file
@ -1,9 +1,12 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file ppm.h
|
||||
* @addtogroup OpenPilotSystem OpenPilot System
|
||||
* @{
|
||||
* @addtogroup OpenPilotLibraries OpenPilot System Libraries
|
||||
* @{
|
||||
* @file alarms.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @brief Sends or Receives the ppm values to/from the remote unit
|
||||
* @brief Include file of the alarm library
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
*
|
||||
*****************************************************************************/
|
||||
@ -22,19 +25,26 @@
|
||||
* with this program; if not, write to the Free Software Foundation, Inc.,
|
||||
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
*/
|
||||
#ifndef ALARMS_H
|
||||
#define ALARMS_H
|
||||
|
||||
#ifndef PPM_H_
|
||||
#define PPM_H_
|
||||
#include "systemalarms.h"
|
||||
#define SYSTEMALARMS_ALARM_DEFAULT SYSTEMALARMS_ALARM_UNINITIALISED
|
||||
|
||||
#include "stdint.h"
|
||||
int32_t AlarmsInitialize(void);
|
||||
int32_t AlarmsSet(SystemAlarmsAlarmElem alarm, SystemAlarmsAlarmOptions severity);
|
||||
SystemAlarmsAlarmOptions AlarmsGet(SystemAlarmsAlarmElem alarm);
|
||||
int32_t AlarmsDefault(SystemAlarmsAlarmElem alarm);
|
||||
void AlarmsDefaultAll();
|
||||
int32_t AlarmsClear(SystemAlarmsAlarmElem alarm);
|
||||
void AlarmsClearAll();
|
||||
int32_t AlarmsHasWarnings();
|
||||
int32_t AlarmsHasErrors();
|
||||
int32_t AlarmsHasCritical();
|
||||
|
||||
// *************************************************************
|
||||
#endif // ALARMS_H
|
||||
|
||||
void ppm_1ms_tick(void);
|
||||
void ppm_process(void);
|
||||
void ppm_deinit(void);
|
||||
void ppm_init(uint32_t our_sn);
|
||||
|
||||
// *************************************************************
|
||||
|
||||
#endif
|
||||
/**
|
||||
* @}
|
||||
* @}
|
||||
*/
|
51
flight/PipXtreme/reserved/api_comms.h → flight/PipXtreme/System/inc/op_config.h
Normal file → Executable file
51
flight/PipXtreme/reserved/api_comms.h → flight/PipXtreme/System/inc/op_config.h
Normal file → Executable file
@ -1,40 +1,39 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup OpenPilotSystem OpenPilot System
|
||||
* @{
|
||||
* @addtogroup OpenPilotCore OpenPilot Core
|
||||
* @{
|
||||
*
|
||||
* @file api_comms.h
|
||||
* @file op_config.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @brief RF Module hardware layer
|
||||
* @brief OpenPilot configuration header.
|
||||
* Compile time config for OpenPilot Application
|
||||
* @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
|
||||
/*
|
||||
* 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
|
||||
*
|
||||
* 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.,
|
||||
*
|
||||
* 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 __API_COMMS_H__
|
||||
#define __API_COMMS_H__
|
||||
|
||||
#include "stdint.h"
|
||||
#ifndef OP_CONFIG_H
|
||||
#define OP_CONFIG_H
|
||||
|
||||
// *****************************************************************************
|
||||
|
||||
void api_1ms_tick(void);
|
||||
void api_process(void);
|
||||
|
||||
void api_init(void);
|
||||
|
||||
// *****************************************************************************
|
||||
|
||||
#endif
|
||||
#endif /* OP_CONFIG_H */
|
||||
/**
|
||||
* @}
|
||||
* @}
|
||||
*/
|
62
flight/PipXtreme/inc/crc.h → flight/PipXtreme/System/inc/openpilot.h
Normal file → Executable file
62
flight/PipXtreme/inc/crc.h → flight/PipXtreme/System/inc/openpilot.h
Normal file → Executable file
@ -1,43 +1,53 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file crc.h
|
||||
* @addtogroup OpenPilotSystem OpenPilot System
|
||||
* @{
|
||||
* @addtogroup OpenPilotCore OpenPilot Core
|
||||
* @{
|
||||
* @file openpilot.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @brief Serial communication port handling routines
|
||||
* @brief Main OpenPilot 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
|
||||
/*
|
||||
* 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
|
||||
*
|
||||
* 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.,
|
||||
*
|
||||
* 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 _CRC_H_
|
||||
#define _CRC_H_
|
||||
|
||||
#include "stm32f10x.h"
|
||||
#ifndef OPENPILOT_H
|
||||
#define OPENPILOT_H
|
||||
|
||||
// ********************************************************************
|
||||
|
||||
uint16_t updateCRC16(uint16_t crc, uint8_t b);
|
||||
uint16_t updateCRC16Data(uint16_t crc, void *data, uint32_t len);
|
||||
/* PIOS Includes */
|
||||
#include <pios.h>
|
||||
|
||||
uint32_t updateCRC32(uint32_t crc, uint8_t b);
|
||||
uint32_t updateCRC32Data(uint32_t crc, void *data, uint32_t len);
|
||||
/* OpenPilot Libraries */
|
||||
#include "op_config.h"
|
||||
#include "utlist.h"
|
||||
#include "uavobjectmanager.h"
|
||||
#include "eventdispatcher.h"
|
||||
#include "alarms.h"
|
||||
#include "taskmonitor.h"
|
||||
#include "uavtalk.h"
|
||||
|
||||
void CRC_init(void);
|
||||
/* Global Functions */
|
||||
void OpenPilotInit(void);
|
||||
|
||||
// ********************************************************************
|
||||
|
||||
#endif
|
||||
#endif /* OPENPILOT_H */
|
||||
/**
|
||||
* @}
|
||||
* @}
|
||||
*/
|
84
flight/PipXtreme/System/inc/pios_board_posix.h
Executable file
84
flight/PipXtreme/System/inc/pios_board_posix.h
Executable file
@ -0,0 +1,84 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file pios_board.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @brief Defines board hardware for the OpenPilot Version 1.1 hardware.
|
||||
* @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_BOARD_H
|
||||
#define PIOS_BOARD_H
|
||||
|
||||
|
||||
|
||||
|
||||
//------------------------
|
||||
// PIOS_LED
|
||||
//------------------------
|
||||
//#define PIOS_LED_LED1_GPIO_PORT GPIOC
|
||||
//#define PIOS_LED_LED1_GPIO_PIN GPIO_Pin_12
|
||||
//#define PIOS_LED_LED1_GPIO_CLK RCC_APB2Periph_GPIOC
|
||||
//#define PIOS_LED_LED2_GPIO_PORT GPIOC
|
||||
//#define PIOS_LED_LED2_GPIO_PIN GPIO_Pin_13
|
||||
//#define PIOS_LED_LED2_GPIO_CLK RCC_APB2Periph_GPIOC
|
||||
#define PIOS_LED_NUM 2
|
||||
//#define PIOS_LED_PORTS { PIOS_LED_LED1_GPIO_PORT, PIOS_LED_LED2_GPIO_PORT }
|
||||
//#define PIOS_LED_PINS { PIOS_LED_LED1_GPIO_PIN, PIOS_LED_LED2_GPIO_PIN }
|
||||
//#define PIOS_LED_CLKS { PIOS_LED_LED1_GPIO_CLK, PIOS_LED_LED2_GPIO_CLK }
|
||||
|
||||
|
||||
//-------------------------
|
||||
// COM
|
||||
//
|
||||
// See also pios_board_posix.c
|
||||
//-------------------------
|
||||
//#define PIOS_USART_TX_BUFFER_SIZE 256
|
||||
#define PIOS_COM_BUFFER_SIZE 1024
|
||||
#define PIOS_UDP_RX_BUFFER_SIZE PIOS_COM_BUFFER_SIZE
|
||||
|
||||
#define PIOS_COM_TELEM_RF 0
|
||||
#define PIOS_COM_GPS 1
|
||||
#define PIOS_COM_TELEM_USB 2
|
||||
|
||||
#ifdef PIOS_ENABLE_AUX_UART
|
||||
#define PIOS_COM_AUX 3
|
||||
#define PIOS_COM_DEBUG PIOS_COM_AUX
|
||||
#endif
|
||||
|
||||
/**
|
||||
* glue macros for file IO
|
||||
* STM32 uses DOSFS for file IO
|
||||
*/
|
||||
#define PIOS_FOPEN_READ(filename,file) (file=fopen((char*)filename,"r"))==NULL
|
||||
|
||||
#define PIOS_FOPEN_WRITE(filename,file) (file=fopen((char*)filename,"w"))==NULL
|
||||
|
||||
#define PIOS_FREAD(file,bufferadr,length,resultadr) (*resultadr=fread((uint8_t*)bufferadr,1,length,*file)) != length
|
||||
|
||||
#define PIOS_FWRITE(file,bufferadr,length,resultadr) *resultadr=fwrite((uint8_t*)bufferadr,1,length,*file)
|
||||
|
||||
|
||||
|
||||
#define PIOS_FCLOSE(file) fclose(file)
|
||||
|
||||
#define PIOS_FUNLINK(file) unlink((char*)filename)
|
||||
|
||||
#endif /* PIOS_BOARD_H */
|
103
flight/PipXtreme/System/inc/pios_config.h
Executable file
103
flight/PipXtreme/System/inc/pios_config.h
Executable file
@ -0,0 +1,103 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup OpenPilotSystem OpenPilot System
|
||||
* @{
|
||||
* @addtogroup OpenPilotCore OpenPilot Core
|
||||
* @{
|
||||
*
|
||||
* @file pios_config.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @brief PiOS configuration header.
|
||||
* Central compile time config for the project.
|
||||
* In particular, pios_config.h is where you define which PiOS libraries
|
||||
* and features are included in the firmware.
|
||||
* @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_CONFIG_H
|
||||
#define PIOS_CONFIG_H
|
||||
|
||||
/* Enable/Disable PiOS Modules */
|
||||
#define PIOS_INCLUDE_DELAY
|
||||
#define PIOS_INCLUDE_IRQ
|
||||
#define PIOS_INCLUDE_LED
|
||||
#define PIOS_INCLUDE_IAP
|
||||
#define PIOS_INCLUDE_RFM22B
|
||||
#define PIOS_INCLUDE_RCVR
|
||||
#define PIOS_INCLUDE_TIM
|
||||
|
||||
/* Supported receiver interfaces */
|
||||
#define PIOS_INCLUDE_PPM
|
||||
|
||||
/* Supported USART-based PIOS modules */
|
||||
#define PIOS_INCLUDE_SPI
|
||||
#define PIOS_INCLUDE_SYS
|
||||
#define PIOS_INCLUDE_USART
|
||||
#define PIOS_INCLUDE_USB
|
||||
#define PIOS_INCLUDE_USB_HID
|
||||
#define PIOS_INCLUDE_USB_CDC
|
||||
#define PIOS_INCLUDE_COM
|
||||
#define PIOS_INCLUDE_SETTINGS
|
||||
#define PIOS_INCLUDE_FREERTOS
|
||||
#define PIOS_INCLUDE_GPIO
|
||||
#define PIOS_INCLUDE_EXTI
|
||||
#define PIOS_INCLUDE_RTC
|
||||
#define PIOS_INCLUDE_WDG
|
||||
#define PIOS_INCLUDE_BL_HELPER
|
||||
#define PIOS_INCLUDE_FLASH_EEPROM
|
||||
|
||||
/* Defaults for Logging */
|
||||
#define LOG_FILENAME "PIOS.LOG"
|
||||
#define STARTUP_LOG_ENABLED 1
|
||||
|
||||
/* COM Module */
|
||||
#define GPS_BAUDRATE 19200
|
||||
#define TELEM_BAUDRATE 19200
|
||||
#define AUXUART_ENABLED 0
|
||||
#define AUXUART_BAUDRATE 19200
|
||||
|
||||
/* Alarm Thresholds */
|
||||
#define HEAP_LIMIT_WARNING 220
|
||||
#define HEAP_LIMIT_CRITICAL 40
|
||||
#define IRQSTACK_LIMIT_WARNING 100
|
||||
#define IRQSTACK_LIMIT_CRITICAL 60
|
||||
#define CPULOAD_LIMIT_WARNING 85
|
||||
#define CPULOAD_LIMIT_CRITICAL 95
|
||||
|
||||
/* Task stack sizes */
|
||||
#define PIOS_ACTUATOR_STACK_SIZE 1020
|
||||
#define PIOS_MANUAL_STACK_SIZE 724
|
||||
#define PIOS_SYSTEM_STACK_SIZE 460
|
||||
#define PIOS_STABILIZATION_STACK_SIZE 524
|
||||
#define PIOS_TELEM_STACK_SIZE 500
|
||||
#define PIOS_EVENTDISPATCHER_STACK_SIZE 130
|
||||
#define IDLE_COUNTS_PER_SEC_AT_NO_LOAD 1995998
|
||||
//#define PIOS_QUATERNION_STABILIZATION
|
||||
|
||||
// This can't be too high to stop eventdispatcher thread overflowing
|
||||
#define PIOS_EVENTDISAPTCHER_QUEUE 10
|
||||
|
||||
/* PIOS Initcall infrastructure */
|
||||
#define PIOS_INCLUDE_INITCALL
|
||||
|
||||
#endif /* PIOS_CONFIG_H */
|
||||
/**
|
||||
* @}
|
||||
* @}
|
||||
*/
|
63
flight/PipXtreme/inc/pios_config.h → flight/PipXtreme/System/inc/pios_config_posix.h
Normal file → Executable file
63
flight/PipXtreme/inc/pios_config.h → flight/PipXtreme/System/inc/pios_config_posix.h
Normal file → Executable file
@ -1,45 +1,54 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file pios_config.h
|
||||
* @file pios_config.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @brief PiOS configuration header.
|
||||
* - Central compile time config for the project.
|
||||
* @brief PiOS configuration header.
|
||||
* Central compile time config for the project.
|
||||
* @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
|
||||
/*
|
||||
* 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
|
||||
*
|
||||
* 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.,
|
||||
*
|
||||
* 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_CONFIG_H
|
||||
#define PIOS_CONFIG_H
|
||||
#ifndef PIOS_CONFIG_POSIX_H
|
||||
#define PIOS_CONFIG_POSIX_H
|
||||
|
||||
|
||||
/* Enable/Disable PiOS Modules */
|
||||
#define PIOS_INCLUDE_ADC
|
||||
#define PIOS_INCLUDE_DELAY
|
||||
#define PIOS_INCLUDE_IRQ
|
||||
#define PIOS_INCLUDE_LED
|
||||
#define PIOS_INCLUDE_SPI
|
||||
#define PIOS_INCLUDE_SYS
|
||||
#define PIOS_INCLUDE_USART
|
||||
#define PIOS_INCLUDE_DELAY
|
||||
#define PIOS_INCLUDE_LED
|
||||
#define PIOS_INCLUDE_SDCARD
|
||||
#define PIOS_INCLUDE_FREERTOS
|
||||
#define PIOS_INCLUDE_COM
|
||||
#define PIOS_INCLUDE_GPIO
|
||||
#define PIOS_INCLUDE_EXTI
|
||||
#define PIOS_INCLUDE_USB
|
||||
#define PIOS_INCLUDE_USB_HID
|
||||
#define PIOS_INCLUDE_UDP
|
||||
#define PIOS_INCLUDE_SERVO
|
||||
|
||||
#endif /* PIOS_CONFIG_H */
|
||||
|
||||
/* Defaults for Logging */
|
||||
#define LOG_FILENAME "PIOS.LOG"
|
||||
#define STARTUP_LOG_ENABLED 1
|
||||
|
||||
/* COM Module */
|
||||
#define GPS_BAUDRATE 19200
|
||||
#define TELEM_BAUDRATE 19200
|
||||
#define AUXUART_ENABLED 0
|
||||
#define AUXUART_BAUDRATE 19200
|
||||
|
||||
|
||||
#endif /* PIOS_CONFIG_POSIX_H */
|
@ -31,11 +31,13 @@
|
||||
#ifndef PIOS_USB_BOARD_DATA_H
|
||||
#define PIOS_USB_BOARD_DATA_H
|
||||
|
||||
#define PIOS_USB_BOARD_CDC_DATA_LENGTH 64
|
||||
#define PIOS_USB_BOARD_CDC_MGMT_LENGTH 32
|
||||
#define PIOS_USB_BOARD_HID_DATA_LENGTH 64
|
||||
|
||||
#define PIOS_USB_BOARD_EP_NUM 2
|
||||
#define PIOS_USB_BOARD_EP_NUM 4
|
||||
|
||||
#include "pios_usb_defs.h" /* struct usb_* */
|
||||
#include "pios_usb_defs.h" /* USB_* macros */
|
||||
|
||||
#define PIOS_USB_BOARD_PRODUCT_ID USB_PRODUCT_ID_PIPXTREME
|
||||
#define PIOS_USB_BOARD_DEVICE_VER USB_OP_DEVICE_VER(USB_OP_BOARD_ID_PIPXTREME, USB_OP_BOARD_MODE_FW)
|
398
flight/PipXtreme/System/pios_board.c
Normal file
398
flight/PipXtreme/System/pios_board.c
Normal file
@ -0,0 +1,398 @@
|
||||
/* -*- Mode: c; c-basic-offset: 2; tab-width: 2; indent-tabs-mode: t -*- */
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup OpenPilotSystem OpenPilot System
|
||||
* @{
|
||||
* @addtogroup OpenPilotCore OpenPilot Core
|
||||
* @{
|
||||
*
|
||||
* @file pios_board.c
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @brief Defines board specific static initializers for hardware for the OpenPilot board.
|
||||
* @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 <openpilot.h>
|
||||
#include <pipxsettings.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 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_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_trans_com_id = 0;
|
||||
uint32_t pios_com_debug_id = 0;
|
||||
uint32_t pios_com_rfm22b_id = 0;
|
||||
uint32_t pios_rfm22b_id = 0;
|
||||
uint32_t pios_ppm_rcvr_id = 0;
|
||||
|
||||
/**
|
||||
* PIOS_Board_Init()
|
||||
* initializes all the core subsystems on this specific hardware
|
||||
* called from System/openpilot.c
|
||||
*/
|
||||
void PIOS_Board_Init(void) {
|
||||
|
||||
/* Delay system */
|
||||
PIOS_DELAY_Init();
|
||||
|
||||
/* Set up the SPI interface to the serial flash */
|
||||
if (PIOS_SPI_Init(&pios_spi_port_id, &pios_spi_port_cfg)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
|
||||
/* Initialize UAVObject libraries */
|
||||
EventDispatcherInitialize();
|
||||
UAVObjInitialize();
|
||||
|
||||
#ifdef PIOS_INCLUDE_WDG
|
||||
/* Initialize watchdog as early as possible to catch faults during init */
|
||||
PIOS_WDG_Init();
|
||||
#endif /* PIOS_INCLUDE_WDG */
|
||||
|
||||
#if defined(PIOS_INCLUDE_RTC)
|
||||
/* Initialize the real-time clock and its associated tick */
|
||||
PIOS_RTC_Init(&pios_rtc_main_cfg);
|
||||
#endif /* PIOS_INCLUDE_RTC */
|
||||
|
||||
PipXSettingsInitialize();
|
||||
|
||||
#if defined(PIOS_INCLUDE_LED)
|
||||
PIOS_LED_Init(&pios_led_cfg);
|
||||
#endif /* PIOS_INCLUDE_LED */
|
||||
|
||||
PipXSettingsData pipxSettings;
|
||||
#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);
|
||||
else
|
||||
PipXSettingsGet(&pipxSettings);
|
||||
#else
|
||||
PipXSettingsGet(&pipxSettings);
|
||||
#endif /* PIOS_INCLUDE_FLASH_EEPROM */
|
||||
|
||||
/* Initialize the task monitor library */
|
||||
TaskMonitorInitialize();
|
||||
|
||||
#if defined(PIOS_INCLUDE_TIM)
|
||||
/* Set up pulse timers */
|
||||
PIOS_TIM_InitClock(&tim_1_cfg);
|
||||
PIOS_TIM_InitClock(&tim_2_cfg);
|
||||
PIOS_TIM_InitClock(&tim_3_cfg);
|
||||
PIOS_TIM_InitClock(&tim_4_cfg);
|
||||
#endif /* PIOS_INCLUDE_TIM */
|
||||
|
||||
#if defined(PIOS_INCLUDE_PACKET_HANDLER)
|
||||
pios_packet_handler = PHInitialize(&pios_ph_cfg);
|
||||
#endif /* PIOS_INCLUDE_PACKET_HANDLER */
|
||||
|
||||
#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_hid_present = false;
|
||||
bool usb_cdc_present = false;
|
||||
|
||||
#if defined(PIOS_INCLUDE_USB_CDC)
|
||||
if (PIOS_USB_DESC_HID_CDC_Init()) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
usb_hid_present = true;
|
||||
usb_cdc_present = true;
|
||||
#else
|
||||
if (PIOS_USB_DESC_HID_ONLY_Init()) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
usb_hid_present = true;
|
||||
#endif
|
||||
|
||||
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.TelemetryConfig)
|
||||
{
|
||||
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)
|
||||
{
|
||||
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);
|
||||
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,
|
||||
rx_buffer, PIOS_COM_TELEM_USB_RX_BUF_LEN,
|
||||
tx_buffer, PIOS_COM_TELEM_USB_TX_BUF_LEN)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_COM */
|
||||
|
||||
#endif /* PIOS_INCLUDE_USB_HID */
|
||||
|
||||
#endif /* PIOS_INCLUDE_USB */
|
||||
|
||||
/* Configure USART1 (telemetry port) */
|
||||
switch (pipxSettings.TelemetryConfig)
|
||||
{
|
||||
case PIPXSETTINGS_TELEMETRYCONFIG_SERIAL:
|
||||
case PIPXSETTINGS_TELEMETRYCONFIG_UAVTALK:
|
||||
case PIPXSETTINGS_TELEMETRYCONFIG_DEBUG:
|
||||
{
|
||||
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);
|
||||
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)) {
|
||||
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_DEBUG:
|
||||
pios_com_debug_id = pios_com_telemetry_id;
|
||||
break;
|
||||
}
|
||||
break;
|
||||
}
|
||||
case PIPXSETTINGS_TELEMETRYCONFIG_DISABLED:
|
||||
break;
|
||||
}
|
||||
|
||||
/* Configure USART3 */
|
||||
switch (pipxSettings.FlexiConfig)
|
||||
{
|
||||
case PIPXSETTINGS_FLEXICONFIG_SERIAL:
|
||||
case PIPXSETTINGS_FLEXICONFIG_UAVTALK:
|
||||
case PIPXSETTINGS_FLEXICONFIG_DEBUG:
|
||||
{
|
||||
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);
|
||||
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)) {
|
||||
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_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);
|
||||
}
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_PPM */
|
||||
case PIPXSETTINGS_FLEXICONFIG_PPM_OUT:
|
||||
case PIPXSETTINGS_FLEXICONFIG_RSSI:
|
||||
case PIPXSETTINGS_FLEXICONFIG_DISABLED:
|
||||
break;
|
||||
}
|
||||
|
||||
#if defined(PIOS_INCLUDE_RFM22B)
|
||||
struct pios_rfm22b_cfg pios_rfm22b_cfg = {
|
||||
.frequencyHz = 434000000,
|
||||
.minFrequencyHz = 434000000 - 2000000,
|
||||
.maxFrequencyHz = 434000000 + 2000000,
|
||||
.RFXtalCap = 0x7f,
|
||||
.maxRFBandwidth = 128000,
|
||||
.maxTxPower = RFM22_tx_pwr_txpow_7, // +20dBm .. 100mW
|
||||
};
|
||||
|
||||
/* Retrieve hardware settings. */
|
||||
pios_rfm22b_cfg.frequencyHz = pipxSettings.Frequency;
|
||||
pios_rfm22b_cfg.RFXtalCap = pipxSettings.FrequencyCalibration;
|
||||
switch (pipxSettings.RFSpeed)
|
||||
{
|
||||
case PIPXSETTINGS_RFSPEED_2400:
|
||||
pios_rfm22b_cfg.maxRFBandwidth = 2000;
|
||||
break;
|
||||
case PIPXSETTINGS_RFSPEED_4800:
|
||||
pios_rfm22b_cfg.maxRFBandwidth = 4000;
|
||||
break;
|
||||
case PIPXSETTINGS_RFSPEED_9600:
|
||||
pios_rfm22b_cfg.maxRFBandwidth = 9600;
|
||||
break;
|
||||
case PIPXSETTINGS_RFSPEED_19200:
|
||||
pios_rfm22b_cfg.maxRFBandwidth = 19200;
|
||||
break;
|
||||
case PIPXSETTINGS_RFSPEED_38400:
|
||||
pios_rfm22b_cfg.maxRFBandwidth = 32000;
|
||||
break;
|
||||
case PIPXSETTINGS_RFSPEED_57600:
|
||||
pios_rfm22b_cfg.maxRFBandwidth = 64000;
|
||||
break;
|
||||
case PIPXSETTINGS_RFSPEED_115200:
|
||||
pios_rfm22b_cfg.maxRFBandwidth = 128000;
|
||||
break;
|
||||
}
|
||||
switch (pipxSettings.RFSpeed)
|
||||
{
|
||||
case PIPXSETTINGS_MAXRFPOWER_125:
|
||||
pios_rfm22b_cfg.maxTxPower = RFM22_tx_pwr_txpow_0;
|
||||
break;
|
||||
case PIPXSETTINGS_MAXRFPOWER_16:
|
||||
pios_rfm22b_cfg.maxTxPower = RFM22_tx_pwr_txpow_1;
|
||||
break;
|
||||
case PIPXSETTINGS_MAXRFPOWER_316:
|
||||
pios_rfm22b_cfg.maxTxPower = RFM22_tx_pwr_txpow_2;
|
||||
break;
|
||||
case PIPXSETTINGS_MAXRFPOWER_63:
|
||||
pios_rfm22b_cfg.maxTxPower = RFM22_tx_pwr_txpow_3;
|
||||
break;
|
||||
case PIPXSETTINGS_MAXRFPOWER_126:
|
||||
pios_rfm22b_cfg.maxTxPower = RFM22_tx_pwr_txpow_4;
|
||||
break;
|
||||
case PIPXSETTINGS_MAXRFPOWER_25:
|
||||
pios_rfm22b_cfg.maxTxPower = RFM22_tx_pwr_txpow_5;
|
||||
break;
|
||||
case PIPXSETTINGS_MAXRFPOWER_50:
|
||||
pios_rfm22b_cfg.maxTxPower = RFM22_tx_pwr_txpow_6;
|
||||
break;
|
||||
case PIPXSETTINGS_MAXRFPOWER_100:
|
||||
pios_rfm22b_cfg.maxTxPower = RFM22_tx_pwr_txpow_7;
|
||||
break;
|
||||
}
|
||||
|
||||
/* Initalize the RFM22B radio COM device. */
|
||||
{
|
||||
if (PIOS_RFM22B_Init(&pios_rfm22b_id, &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_RFM22B */
|
||||
|
||||
/* Remap AFIO pin */
|
||||
GPIO_PinRemapConfig( GPIO_Remap_SWJ_NoJTRST, ENABLE);
|
||||
|
||||
#ifdef PIOS_INCLUDE_ADC
|
||||
PIOS_ADC_Init();
|
||||
#endif
|
||||
PIOS_GPIO_Init();
|
||||
}
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
142
flight/PipXtreme/System/pios_board_posix.c
Executable file
142
flight/PipXtreme/System/pios_board_posix.c
Executable file
@ -0,0 +1,142 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file pios_board.c
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @brief Defines board specific static initializers for hardware for the OpenPilot board.
|
||||
* @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_udp_priv.h>
|
||||
#include <pios_com_priv.h>
|
||||
#include <openpilot.h>
|
||||
#include <uavobjectsinit.h>
|
||||
|
||||
/**
|
||||
* PIOS_Board_Init()
|
||||
* initializes all the core systems on this specific hardware
|
||||
* called from System/openpilot.c
|
||||
*/
|
||||
void PIOS_Board_Init(void) {
|
||||
|
||||
/* Delay system */
|
||||
PIOS_DELAY_Init();
|
||||
|
||||
/* Initialize UAVObject libraries */
|
||||
EventDispatcherInitialize();
|
||||
UAVObjInitialize();
|
||||
|
||||
/* Initialize the alarms library */
|
||||
AlarmsInitialize();
|
||||
|
||||
/* Initialize the task monitor library */
|
||||
TaskMonitorInitialize();
|
||||
|
||||
/* Initialize the PiOS library */
|
||||
PIOS_COM_Init();
|
||||
|
||||
}
|
||||
|
||||
|
||||
const struct pios_udp_cfg pios_udp0_cfg = {
|
||||
.ip = "0.0.0.0",
|
||||
.port = 9000,
|
||||
};
|
||||
const struct pios_udp_cfg pios_udp1_cfg = {
|
||||
.ip = "0.0.0.0",
|
||||
.port = 9001,
|
||||
};
|
||||
const struct pios_udp_cfg pios_udp2_cfg = {
|
||||
.ip = "0.0.0.0",
|
||||
.port = 9002,
|
||||
};
|
||||
|
||||
#ifdef PIOS_COM_AUX
|
||||
/*
|
||||
* AUX USART
|
||||
*/
|
||||
const struct pios_udp_cfg pios_udp3_cfg = {
|
||||
.ip = "0.0.0.0",
|
||||
.port = 9003,
|
||||
};
|
||||
#endif
|
||||
|
||||
/*
|
||||
* Board specific number of devices.
|
||||
*/
|
||||
struct pios_udp_dev pios_udp_devs[] = {
|
||||
#define PIOS_UDP_TELEM 0
|
||||
{
|
||||
.cfg = &pios_udp0_cfg,
|
||||
},
|
||||
#define PIOS_UDP_GPS 1
|
||||
{
|
||||
.cfg = &pios_udp1_cfg,
|
||||
},
|
||||
#define PIOS_UDP_LOCAL 2
|
||||
{
|
||||
.cfg = &pios_udp2_cfg,
|
||||
},
|
||||
#ifdef PIOS_COM_AUX
|
||||
#define PIOS_UDP_AUX 3
|
||||
{
|
||||
.cfg = &pios_udp3_cfg,
|
||||
},
|
||||
#endif
|
||||
};
|
||||
|
||||
uint8_t pios_udp_num_devices = NELEMENTS(pios_udp_devs);
|
||||
|
||||
/*
|
||||
* COM devices
|
||||
*/
|
||||
|
||||
/*
|
||||
* Board specific number of devices.
|
||||
*/
|
||||
extern const struct pios_com_driver pios_serial_com_driver;
|
||||
extern const struct pios_com_driver pios_udp_com_driver;
|
||||
|
||||
struct pios_com_dev pios_com_devs[] = {
|
||||
{
|
||||
.id = PIOS_UDP_TELEM,
|
||||
.driver = &pios_udp_com_driver,
|
||||
},
|
||||
{
|
||||
.id = PIOS_UDP_GPS,
|
||||
.driver = &pios_udp_com_driver,
|
||||
},
|
||||
{
|
||||
.id = PIOS_UDP_LOCAL,
|
||||
.driver = &pios_udp_com_driver,
|
||||
},
|
||||
#ifdef PIOS_COM_AUX
|
||||
{
|
||||
.id = PIOS_UDP_AUX,
|
||||
.driver = &pios_udp_com_driver,
|
||||
},
|
||||
#endif
|
||||
};
|
||||
|
||||
const uint8_t pios_com_num_devices = NELEMENTS(pios_com_devs);
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
99
flight/PipXtreme/System/pipxtreme.c
Executable file
99
flight/PipXtreme/System/pipxtreme.c
Executable file
@ -0,0 +1,99 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup OpenPilotSystem OpenPilot System
|
||||
* @brief These files are the core system files of OpenPilot.
|
||||
* They are the ground layer just above PiOS. In practice, OpenPilot actually starts
|
||||
* in the main() function of openpilot.c
|
||||
* @{
|
||||
* @addtogroup OpenPilotCore OpenPilot Core
|
||||
* @brief This is where the OP firmware starts. Those files also define the compile-time
|
||||
* options of the firmware.
|
||||
* @{
|
||||
* @file openpilot.c
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @brief Sets up and runs main OpenPilot tasks.
|
||||
* @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
|
||||
*/
|
||||
|
||||
|
||||
/* OpenPilot Includes */
|
||||
#include "openpilot.h"
|
||||
#include "uavobjectsinit.h"
|
||||
#include "hwsettings.h"
|
||||
#include "systemmod.h"
|
||||
|
||||
/* Task Priorities */
|
||||
#define PRIORITY_TASK_HOOKS (tskIDLE_PRIORITY + 3)
|
||||
|
||||
/* Global Variables */
|
||||
|
||||
/* Prototype of PIOS_Board_Init() function */
|
||||
extern void PIOS_Board_Init(void);
|
||||
extern void Stack_Change(void);
|
||||
|
||||
/**
|
||||
* OpenPilot Main function:
|
||||
*
|
||||
* Initialize PiOS<BR>
|
||||
* Create the "System" task (SystemModInitializein Modules/System/systemmod.c) <BR>
|
||||
* Start FreeRTOS Scheduler (vTaskStartScheduler) (Now handled by caller)
|
||||
* If something goes wrong, blink LED1 and LED2 every 100ms
|
||||
*
|
||||
*/
|
||||
int main()
|
||||
{
|
||||
/* NOTE: Do NOT modify the following start-up sequence */
|
||||
/* Any new initialization functions should be added in OpenPilotInit() */
|
||||
|
||||
/* Brings up System using CMSIS functions, enables the LEDs. */
|
||||
PIOS_SYS_Init();
|
||||
|
||||
/* Architecture dependant Hardware and
|
||||
* core subsystem initialisation
|
||||
* (see pios_board.c for your arch)
|
||||
* */
|
||||
PIOS_Board_Init();
|
||||
|
||||
/* Initialize modules */
|
||||
MODULE_INITIALISE_ALL
|
||||
|
||||
/* swap the stack to use the IRQ stack */
|
||||
Stack_Change();
|
||||
|
||||
/* Start the FreeRTOS scheduler which should never returns.*/
|
||||
vTaskStartScheduler();
|
||||
|
||||
/* If all is well we will never reach here as the scheduler will now be running. */
|
||||
|
||||
/* Do some indication to user that something bad just happened */
|
||||
while (1) {
|
||||
#if defined(PIOS_LED_HEARTBEAT)
|
||||
PIOS_LED_Toggle(PIOS_LED_HEARTBEAT);
|
||||
#endif /* PIOS_LED_HEARTBEAT */
|
||||
PIOS_DELAY_WaitmS(100);
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* @}
|
||||
* @}
|
||||
*/
|
||||
|
@ -1,852 +0,0 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file apiconfig_config.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @brief RF Module hardware layer
|
||||
* @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 <string.h>
|
||||
|
||||
#include "stm32f10x.h"
|
||||
#include "gpio_in.h"
|
||||
#include "api_config.h"
|
||||
#include "rfm22b.h"
|
||||
#include "packet_handler.h"
|
||||
#include "stream.h"
|
||||
#include "ppm.h"
|
||||
#include "saved_settings.h"
|
||||
#include "crc.h"
|
||||
#include "main.h"
|
||||
#include "pios_usb.h" /* PIOS_USB_* */
|
||||
|
||||
#if defined(PIOS_COM_DEBUG)
|
||||
// #define APICONFIG_DEBUG
|
||||
#endif
|
||||
|
||||
// *****************************************************************************
|
||||
// modem configuration packets
|
||||
|
||||
#define PIPX_HEADER_MARKER 0x76b38a52
|
||||
|
||||
enum {
|
||||
PIPX_PACKET_TYPE_REQ_DETAILS = 0,
|
||||
PIPX_PACKET_TYPE_DETAILS,
|
||||
PIPX_PACKET_TYPE_REQ_SETTINGS,
|
||||
PIPX_PACKET_TYPE_SETTINGS,
|
||||
PIPX_PACKET_TYPE_REQ_STATE,
|
||||
PIPX_PACKET_TYPE_STATE,
|
||||
PIPX_PACKET_TYPE_SPECTRUM
|
||||
};
|
||||
|
||||
typedef struct
|
||||
{
|
||||
uint32_t marker;
|
||||
uint32_t serial_number;
|
||||
uint8_t type;
|
||||
uint8_t spare;
|
||||
uint16_t data_size;
|
||||
uint32_t header_crc;
|
||||
uint32_t data_crc;
|
||||
// uint8_t data[0];
|
||||
} __attribute__((__packed__)) t_pipx_config_header;
|
||||
|
||||
typedef struct
|
||||
{
|
||||
uint8_t major_version;
|
||||
uint8_t minor_version;
|
||||
uint32_t serial_number;
|
||||
uint32_t min_frequency_Hz;
|
||||
uint32_t max_frequency_Hz;
|
||||
uint8_t frequency_band;
|
||||
float frequency_step_size;
|
||||
} __attribute__((__packed__)) t_pipx_config_details;
|
||||
|
||||
typedef struct
|
||||
{
|
||||
uint8_t mode;
|
||||
uint8_t link_state;
|
||||
int16_t rssi;
|
||||
int32_t afc;
|
||||
uint16_t retries;
|
||||
} __attribute__((__packed__)) t_pipx_config_state;
|
||||
|
||||
typedef struct
|
||||
{
|
||||
uint8_t mode;
|
||||
uint32_t serial_baudrate; // serial usart baudrate
|
||||
uint32_t destination_id;
|
||||
uint32_t frequency_Hz;
|
||||
uint32_t max_rf_bandwidth;
|
||||
uint8_t max_tx_power;
|
||||
uint8_t rf_xtal_cap;
|
||||
bool aes_enable;
|
||||
uint8_t aes_key[16];
|
||||
uint8_t rts_time;
|
||||
uint8_t spare[16];
|
||||
} __attribute__((__packed__)) t_pipx_config_settings;
|
||||
|
||||
typedef struct
|
||||
{
|
||||
uint32_t start_frequency;
|
||||
uint16_t frequency_step_size;
|
||||
uint16_t magnitudes;
|
||||
// int8_t magnitude[0];
|
||||
} __attribute__((__packed__)) t_pipx_config_spectrum;
|
||||
|
||||
// *****************************************************************************
|
||||
// local variables
|
||||
|
||||
uint32_t apiconfig_previous_com_port = 0;
|
||||
|
||||
volatile uint16_t apiconfig_rx_config_timer = 0;
|
||||
volatile uint16_t apiconfig_rx_timer = 0;
|
||||
volatile uint16_t apiconfig_tx_timer = 0;
|
||||
volatile uint16_t apiconfig_ss_timer = 0;
|
||||
|
||||
uint8_t apiconfig_rx_buffer[256] __attribute__ ((aligned(4)));
|
||||
uint16_t apiconfig_rx_buffer_wr;
|
||||
|
||||
uint8_t apiconfig_tx_buffer[256] __attribute__ ((aligned(4)));
|
||||
uint16_t apiconfig_tx_buffer_wr;
|
||||
|
||||
uint8_t apiconfig_tx_config_buffer[128] __attribute__ ((aligned(4)));
|
||||
uint16_t apiconfig_tx_config_buffer_wr;
|
||||
|
||||
// for scanning the spectrum
|
||||
int8_t apiconfig_spec_buffer[64] __attribute__ ((aligned(4)));
|
||||
uint16_t apiconfig_spec_buffer_wr;
|
||||
uint32_t apiconfig_spec_start_freq;
|
||||
uint32_t apiconfig_spec_freq;
|
||||
|
||||
bool apiconfig_usb_comms;
|
||||
uint32_t apiconfig_comm_port;
|
||||
|
||||
uint16_t apiconfig_connection_index; // the RF connection we are using
|
||||
|
||||
uint8_t led_counter;
|
||||
|
||||
// *****************************************************************************
|
||||
|
||||
int apiconfig_sendDetailsPacket(void)
|
||||
{
|
||||
if (sizeof(apiconfig_tx_config_buffer) - apiconfig_tx_config_buffer_wr < sizeof(t_pipx_config_header) + sizeof(t_pipx_config_details))
|
||||
return -1; // not enough room in the tx buffer for the packet we were going to send
|
||||
|
||||
t_pipx_config_header *header = (t_pipx_config_header *)(apiconfig_tx_config_buffer + apiconfig_tx_config_buffer_wr);
|
||||
t_pipx_config_details *details = (t_pipx_config_details *)((uint8_t *)header + sizeof(t_pipx_config_header));
|
||||
|
||||
header->marker = PIPX_HEADER_MARKER;
|
||||
header->serial_number = serial_number_crc32;
|
||||
header->type = PIPX_PACKET_TYPE_DETAILS;
|
||||
header->spare = 0;
|
||||
header->data_size = sizeof(t_pipx_config_details);
|
||||
|
||||
details->major_version = VERSION_MAJOR;
|
||||
details->minor_version = VERSION_MINOR;
|
||||
details->serial_number = serial_number_crc32;
|
||||
details->min_frequency_Hz = saved_settings.min_frequency_Hz;
|
||||
details->max_frequency_Hz = saved_settings.max_frequency_Hz;
|
||||
details->frequency_band = saved_settings.frequency_band;
|
||||
details->frequency_step_size = rfm22_getFrequencyStepSize();
|
||||
|
||||
header->data_crc = updateCRC32Data(0xffffffff, details, header->data_size);
|
||||
header->header_crc = 0;
|
||||
header->header_crc = updateCRC32Data(0xffffffff, header, sizeof(t_pipx_config_header));
|
||||
|
||||
int total_packet_size = sizeof(t_pipx_config_header) + header->data_size;
|
||||
|
||||
apiconfig_tx_config_buffer_wr += total_packet_size;
|
||||
|
||||
#if defined(APICONFIG_DEBUG)
|
||||
DEBUG_PRINTF("TX api config: details\r\n");
|
||||
#endif
|
||||
|
||||
return total_packet_size;
|
||||
}
|
||||
|
||||
int apiconfig_sendStatePacket(void)
|
||||
{
|
||||
if (sizeof(apiconfig_tx_config_buffer) - apiconfig_tx_config_buffer_wr < sizeof(t_pipx_config_header) + sizeof(t_pipx_config_state))
|
||||
return -1; // not enough room in the tx buffer for the packet we were going to send
|
||||
|
||||
t_pipx_config_header *header = (t_pipx_config_header *)(apiconfig_tx_config_buffer + apiconfig_tx_config_buffer_wr);
|
||||
t_pipx_config_state *state = (t_pipx_config_state *)((uint8_t *)header + sizeof(t_pipx_config_header));
|
||||
|
||||
header->marker = PIPX_HEADER_MARKER;
|
||||
header->serial_number = serial_number_crc32;
|
||||
header->type = PIPX_PACKET_TYPE_STATE;
|
||||
header->spare = 0;
|
||||
header->data_size = sizeof(t_pipx_config_state);
|
||||
|
||||
state->mode = 0;
|
||||
state->link_state = ph_getCurrentLinkState(0);
|
||||
state->rssi = ph_getLastRSSI(0);
|
||||
state->afc = ph_getLastAFC(0);
|
||||
state->retries = ph_getRetries(0);
|
||||
|
||||
header->data_crc = updateCRC32Data(0xffffffff, state, header->data_size);
|
||||
header->header_crc = 0;
|
||||
header->header_crc = updateCRC32Data(0xffffffff, header, sizeof(t_pipx_config_header));
|
||||
|
||||
int total_packet_size = sizeof(t_pipx_config_header) + header->data_size;
|
||||
|
||||
apiconfig_tx_config_buffer_wr += total_packet_size;
|
||||
|
||||
#if defined(APICONFIG_DEBUG)
|
||||
DEBUG_PRINTF("TX api config: state\r\n");
|
||||
#endif
|
||||
|
||||
return total_packet_size;
|
||||
}
|
||||
|
||||
int apiconfig_sendSettingsPacket(void)
|
||||
{
|
||||
if (sizeof(apiconfig_tx_config_buffer) - apiconfig_tx_config_buffer_wr < sizeof(t_pipx_config_header) + sizeof(t_pipx_config_settings))
|
||||
return -1; // not enough room in the tx buffer for the packet we were going to send
|
||||
|
||||
t_pipx_config_header *header = (t_pipx_config_header *)(apiconfig_tx_config_buffer + apiconfig_tx_config_buffer_wr);
|
||||
t_pipx_config_settings *settings = (t_pipx_config_settings *)((uint8_t *)header + sizeof(t_pipx_config_header));
|
||||
|
||||
header->marker = PIPX_HEADER_MARKER;
|
||||
header->serial_number = serial_number_crc32;
|
||||
header->type = PIPX_PACKET_TYPE_SETTINGS;
|
||||
header->spare = 0;
|
||||
header->data_size = sizeof(t_pipx_config_settings);
|
||||
|
||||
settings->mode = saved_settings.mode;
|
||||
settings->destination_id = saved_settings.destination_id;
|
||||
settings->frequency_Hz = saved_settings.frequency_Hz;
|
||||
settings->max_rf_bandwidth = saved_settings.max_rf_bandwidth;
|
||||
settings->max_tx_power = saved_settings.max_tx_power;
|
||||
settings->rf_xtal_cap = saved_settings.rf_xtal_cap;
|
||||
settings->serial_baudrate = saved_settings.serial_baudrate;
|
||||
settings->aes_enable = saved_settings.aes_enable;
|
||||
memcpy((char *)settings->aes_key, (char *)saved_settings.aes_key, sizeof(settings->aes_key));
|
||||
settings->rts_time = saved_settings.rts_time;
|
||||
memset(settings->spare, 0xff, sizeof(settings->spare));
|
||||
|
||||
header->data_crc = updateCRC32Data(0xffffffff, settings, header->data_size);
|
||||
header->header_crc = 0;
|
||||
header->header_crc = updateCRC32Data(0xffffffff, header, sizeof(t_pipx_config_header));
|
||||
|
||||
int total_packet_size = sizeof(t_pipx_config_header) + header->data_size;
|
||||
|
||||
apiconfig_tx_config_buffer_wr += total_packet_size;
|
||||
|
||||
#if defined(APICONFIG_DEBUG)
|
||||
DEBUG_PRINTF("TX api config: settings\r\n");
|
||||
#endif
|
||||
|
||||
return total_packet_size;
|
||||
}
|
||||
|
||||
int apiconfig_sendSpectrumPacket(uint32_t start_frequency, uint16_t freq_step_size, void *spectrum_data, uint32_t spectrum_data_size)
|
||||
{
|
||||
if (sizeof(apiconfig_tx_config_buffer) - apiconfig_tx_config_buffer_wr < sizeof(t_pipx_config_header) + sizeof(t_pipx_config_spectrum) + spectrum_data_size)
|
||||
return -1; // not enough room in the tx buffer for the packet we were going to send
|
||||
|
||||
if (!spectrum_data || spectrum_data_size <= 0)
|
||||
return -2; // nothing to send
|
||||
|
||||
t_pipx_config_header *header = (t_pipx_config_header *)(apiconfig_tx_config_buffer + apiconfig_tx_config_buffer_wr);
|
||||
t_pipx_config_spectrum *spectrum = (t_pipx_config_spectrum *)((uint8_t *)header + sizeof(t_pipx_config_header));
|
||||
uint8_t *data = (uint8_t *)spectrum + sizeof(t_pipx_config_spectrum);
|
||||
|
||||
header->marker = PIPX_HEADER_MARKER;
|
||||
header->serial_number = serial_number_crc32;
|
||||
header->type = PIPX_PACKET_TYPE_SPECTRUM;
|
||||
header->spare = 0;
|
||||
header->data_size = sizeof(t_pipx_config_spectrum) + spectrum_data_size;
|
||||
|
||||
spectrum->start_frequency = start_frequency;
|
||||
spectrum->frequency_step_size = freq_step_size;
|
||||
spectrum->magnitudes = spectrum_data_size;
|
||||
memmove(data, spectrum_data, spectrum_data_size);
|
||||
|
||||
header->data_crc = updateCRC32Data(0xffffffff, spectrum, header->data_size);
|
||||
header->header_crc = 0;
|
||||
header->header_crc = updateCRC32Data(0xffffffff, header, sizeof(t_pipx_config_header));
|
||||
|
||||
int total_packet_size = sizeof(t_pipx_config_header) + header->data_size;
|
||||
|
||||
apiconfig_tx_config_buffer_wr += total_packet_size;
|
||||
|
||||
#if defined(APICONFIG_DEBUG)
|
||||
DEBUG_PRINTF("TX api config: spectrum\r\n");
|
||||
#endif
|
||||
|
||||
return total_packet_size;
|
||||
}
|
||||
|
||||
void apiconfig_processInputPacket(void *buf, uint16_t len)
|
||||
{
|
||||
if (len <= 0)
|
||||
return;
|
||||
|
||||
t_pipx_config_header *header = (t_pipx_config_header *)buf;
|
||||
uint8_t *data = (uint8_t *)header + sizeof(t_pipx_config_header);
|
||||
|
||||
switch (header->type)
|
||||
{
|
||||
case PIPX_PACKET_TYPE_REQ_DETAILS:
|
||||
|
||||
#if defined(APICONFIG_DEBUG)
|
||||
DEBUG_PRINTF("RX api config: req_details\r\n");
|
||||
#endif
|
||||
|
||||
if (header->serial_number == 0 || header->serial_number == 0xffffffff || header->serial_number == serial_number_crc32)
|
||||
apiconfig_sendDetailsPacket();
|
||||
|
||||
break;
|
||||
|
||||
case PIPX_PACKET_TYPE_REQ_STATE:
|
||||
|
||||
#if defined(APICONFIG_DEBUG)
|
||||
DEBUG_PRINTF("RX api config: req_state\r\n");
|
||||
#endif
|
||||
|
||||
if (header->serial_number == serial_number_crc32)
|
||||
apiconfig_sendStatePacket();
|
||||
|
||||
break;
|
||||
|
||||
case PIPX_PACKET_TYPE_REQ_SETTINGS: // they are requesting our configuration
|
||||
|
||||
#if defined(APICONFIG_DEBUG)
|
||||
DEBUG_PRINTF("RX api config: req_settings\r\n");
|
||||
#endif
|
||||
|
||||
if (header->serial_number == serial_number_crc32)
|
||||
apiconfig_sendSettingsPacket();
|
||||
|
||||
break;
|
||||
|
||||
case PIPX_PACKET_TYPE_SETTINGS: // they have sent us new configuration settings
|
||||
#if defined(APICONFIG_DEBUG)
|
||||
DEBUG_PRINTF("RX api config: settings\r\n");
|
||||
#endif
|
||||
|
||||
if (header->serial_number == serial_number_crc32)
|
||||
{ // the packet is meant for us
|
||||
|
||||
booting = true;
|
||||
|
||||
ph_set_remote_serial_number(0, 0); // stop the packet handler trying to communicate
|
||||
|
||||
// ******
|
||||
// save the new settings
|
||||
|
||||
t_pipx_config_settings *settings = (t_pipx_config_settings *)data;
|
||||
|
||||
saved_settings.mode = settings->mode;
|
||||
saved_settings.destination_id = settings->destination_id;
|
||||
saved_settings.frequency_Hz = settings->frequency_Hz;
|
||||
saved_settings.max_tx_power = settings->max_tx_power;
|
||||
saved_settings.max_rf_bandwidth = settings->max_rf_bandwidth;
|
||||
saved_settings.rf_xtal_cap = settings->rf_xtal_cap;
|
||||
saved_settings.serial_baudrate = settings->serial_baudrate;
|
||||
saved_settings.aes_enable = settings->aes_enable;
|
||||
memcpy((char *)saved_settings.aes_key, (char *)settings->aes_key, sizeof(saved_settings.aes_key));
|
||||
saved_settings.rts_time = settings->rts_time;
|
||||
|
||||
saved_settings_save(); // save them into flash
|
||||
|
||||
// ******
|
||||
|
||||
ph_deinit();
|
||||
stream_deinit();
|
||||
ppm_deinit();
|
||||
|
||||
PIOS_COM_ChangeBaud(PIOS_COM_SERIAL, saved_settings.serial_baudrate);
|
||||
|
||||
switch (saved_settings.mode)
|
||||
{
|
||||
case MODE_NORMAL: // normal 2-way packet mode
|
||||
case MODE_STREAM_TX: // 1-way continuous tx packet mode
|
||||
case MODE_STREAM_RX: // 1-way continuous rx packet mode
|
||||
case MODE_PPM_TX: // PPM tx mode
|
||||
case MODE_PPM_RX: // PPM rx mode
|
||||
case MODE_SCAN_SPECTRUM: // scan the receiver over the whole band
|
||||
case MODE_TX_BLANK_CARRIER_TEST: // blank carrier Tx mode (for calibrating the carrier frequency say)
|
||||
case MODE_TX_SPECTRUM_TEST: // pseudo random Tx data mode (for checking the Tx carrier spectrum)
|
||||
break;
|
||||
default: // unknown mode
|
||||
saved_settings.mode = MODE_NORMAL;
|
||||
break;
|
||||
}
|
||||
|
||||
switch (saved_settings.mode)
|
||||
{
|
||||
case MODE_NORMAL: // normal 2-way packet mode
|
||||
ph_init(serial_number_crc32); // initialise the packet handler
|
||||
break;
|
||||
|
||||
case MODE_STREAM_TX: // 1-way continuous tx packet mode
|
||||
case MODE_STREAM_RX: // 1-way continuous rx packet mode
|
||||
stream_init(serial_number_crc32); // initialise the continuous packet stream module
|
||||
break;
|
||||
|
||||
case MODE_PPM_TX: // PPM tx mode
|
||||
case MODE_PPM_RX: // PPM rx mode
|
||||
ppm_init(serial_number_crc32); // initialise the PPM module
|
||||
break;
|
||||
|
||||
case MODE_SCAN_SPECTRUM: // scan the receiver over the whole band
|
||||
rfm22_init_scan_spectrum(saved_settings.min_frequency_Hz, saved_settings.max_frequency_Hz);
|
||||
rfm22_setFreqCalibration(saved_settings.rf_xtal_cap);
|
||||
apiconfig_spec_start_freq = saved_settings.min_frequency_Hz;
|
||||
apiconfig_spec_freq = apiconfig_spec_start_freq;
|
||||
apiconfig_spec_buffer_wr = 0;
|
||||
apiconfig_ss_timer = 0;
|
||||
break;
|
||||
|
||||
case MODE_TX_BLANK_CARRIER_TEST: // blank carrier Tx mode (for calibrating the carrier frequency say)
|
||||
rfm22_init_normal(saved_settings.min_frequency_Hz, saved_settings.max_frequency_Hz, rfm22_freqHopSize());
|
||||
rfm22_setFreqCalibration(saved_settings.rf_xtal_cap);
|
||||
rfm22_setNominalCarrierFrequency(saved_settings.frequency_Hz);
|
||||
rfm22_setDatarate(saved_settings.max_rf_bandwidth, TRUE);
|
||||
rfm22_setTxPower(saved_settings.max_tx_power);
|
||||
rfm22_setTxCarrierMode();
|
||||
break;
|
||||
|
||||
case MODE_TX_SPECTRUM_TEST: // pseudo random Tx data mode (for checking the Tx carrier spectrum)
|
||||
rfm22_init_normal(saved_settings.min_frequency_Hz, saved_settings.max_frequency_Hz, rfm22_freqHopSize());
|
||||
rfm22_setFreqCalibration(saved_settings.rf_xtal_cap);
|
||||
rfm22_setNominalCarrierFrequency(saved_settings.frequency_Hz);
|
||||
rfm22_setDatarate(saved_settings.max_rf_bandwidth, TRUE);
|
||||
rfm22_setTxPower(saved_settings.max_tx_power);
|
||||
rfm22_setTxPNMode();
|
||||
break;
|
||||
}
|
||||
|
||||
// ******
|
||||
|
||||
booting = false;
|
||||
}
|
||||
|
||||
break;
|
||||
|
||||
default:
|
||||
#if defined(APICONFIG_DEBUG)
|
||||
DEBUG_PRINTF("RX api config: unknown type [%u]\r\n", header->type);
|
||||
#endif
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
uint16_t apiconfig_scanForConfigPacket(void *buf, uint16_t *len, bool rf_packet)
|
||||
{
|
||||
uint16_t length = *len;
|
||||
uint16_t i = 0;
|
||||
|
||||
while (TRUE)
|
||||
{
|
||||
uint32_t crc1, crc2;
|
||||
|
||||
t_pipx_config_header *header = (t_pipx_config_header *)buf + i;
|
||||
uint8_t *data = (uint8_t *)header + sizeof(t_pipx_config_header);
|
||||
|
||||
if (i + sizeof(t_pipx_config_header) > length)
|
||||
{ // not enough data for a packet
|
||||
if (i >= sizeof(header->marker))
|
||||
i -= sizeof(header->marker);
|
||||
else
|
||||
i = 0;
|
||||
break;
|
||||
}
|
||||
|
||||
if (header->marker != PIPX_HEADER_MARKER)
|
||||
{ // no packet marker found
|
||||
i++;
|
||||
continue;
|
||||
}
|
||||
|
||||
// check the header is error free
|
||||
crc1 = header->header_crc;
|
||||
header->header_crc = 0;
|
||||
crc2 = updateCRC32Data(0xffffffff, header, sizeof(t_pipx_config_header));
|
||||
header->header_crc = crc1;
|
||||
if (crc2 != crc1)
|
||||
{ // faulty header or not really a header
|
||||
i++;
|
||||
continue;
|
||||
}
|
||||
|
||||
// valid header found!
|
||||
|
||||
#if defined(APICONFIG_DEBUG)
|
||||
DEBUG_PRINTF("RX api config: header found\r\n");
|
||||
#endif
|
||||
|
||||
if (!rf_packet)
|
||||
{
|
||||
apiconfig_rx_config_timer = 0; // reset timer
|
||||
apiconfig_rx_timer = 0; // reset the timer
|
||||
}
|
||||
|
||||
int total_packet_size = sizeof(t_pipx_config_header) + header->data_size;
|
||||
|
||||
if (i + total_packet_size > length)
|
||||
{ // not yet got a full packet
|
||||
break;
|
||||
}
|
||||
|
||||
if (header->data_size > 0)
|
||||
{ // check the data is error free
|
||||
crc1 = header->data_crc;
|
||||
crc2 = updateCRC32Data(0xffffffff, data, header->data_size);
|
||||
if (crc2 != crc1)
|
||||
{ // faulty data .. remove the entire packet
|
||||
length -= total_packet_size;
|
||||
if (length - i > 0)
|
||||
memmove(buf + i, buf + i + total_packet_size, length - i);
|
||||
continue;
|
||||
}
|
||||
}
|
||||
|
||||
if (!rf_packet)
|
||||
apiconfig_processInputPacket(buf + i, length - i);
|
||||
|
||||
// remove the packet from the buffer
|
||||
length -= total_packet_size;
|
||||
if (length - i > 0)
|
||||
memmove(buf + i, buf + i + total_packet_size, length - i);
|
||||
|
||||
break;
|
||||
}
|
||||
|
||||
*len = length;
|
||||
|
||||
return i;
|
||||
}
|
||||
|
||||
// *****************************************************************************
|
||||
// send the data received from the local comm-port to the RF packet handler TX buffer
|
||||
|
||||
void apiconfig_processTx(void)
|
||||
{
|
||||
while (TRUE)
|
||||
{
|
||||
// scan for a configuration packet in the rx buffer
|
||||
uint16_t data_size = apiconfig_scanForConfigPacket(apiconfig_rx_buffer, &apiconfig_rx_buffer_wr, false);
|
||||
|
||||
uint16_t time_out = 5; // ms
|
||||
if (!apiconfig_usb_comms) time_out = (15000 * sizeof(t_pipx_config_header)) / saved_settings.serial_baudrate; // allow enough time to rx a config header
|
||||
if (time_out < 5) time_out = 5;
|
||||
|
||||
if (data_size == 0 && apiconfig_rx_timer >= time_out)
|
||||
// no config packet found in the buffer within the timeout period, treat any data in the buffer as data to be sent over the air
|
||||
data_size = apiconfig_rx_buffer_wr;
|
||||
|
||||
if (data_size == 0)
|
||||
break; // no data to send over the air
|
||||
|
||||
if (saved_settings.mode == MODE_NORMAL || saved_settings.mode == MODE_STREAM_TX)
|
||||
{
|
||||
// free space size in the RF packet handler tx buffer
|
||||
uint16_t ph_num = ph_putData_free(apiconfig_connection_index);
|
||||
|
||||
// set the USART RTS handshaking line
|
||||
if (!apiconfig_usb_comms && ph_connected(apiconfig_connection_index))
|
||||
{
|
||||
if (ph_num < 32)
|
||||
SERIAL_RTS_CLEAR; // lower the USART RTS line - we don't have space in the buffer for anymore bytes
|
||||
else
|
||||
SERIAL_RTS_SET; // release the USART RTS line - we have space in the buffer for now bytes
|
||||
}
|
||||
else
|
||||
SERIAL_RTS_SET; // release the USART RTS line
|
||||
|
||||
#if defined(APICONFIG_DEBUG)
|
||||
DEBUG_PRINTF("RX api config: data size %u\r\n", data_size);
|
||||
#endif
|
||||
|
||||
if (ph_connected(apiconfig_connection_index))
|
||||
{ // we have an RF link to a remote modem
|
||||
|
||||
if (ph_num < data_size)
|
||||
break; // not enough room in the RF packet handler TX buffer for the data
|
||||
|
||||
// copy the data into the RF packet handler TX buffer for sending over the RF link
|
||||
data_size = ph_putData(apiconfig_connection_index, apiconfig_rx_buffer, data_size);
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
SERIAL_RTS_SET; // release the USART RTS line - we have space in the buffer for now bytes
|
||||
}
|
||||
|
||||
// remove the data from our RX buffer
|
||||
apiconfig_rx_buffer_wr -= data_size;
|
||||
if (apiconfig_rx_buffer_wr > 0)
|
||||
memmove(apiconfig_rx_buffer, apiconfig_rx_buffer + data_size, apiconfig_rx_buffer_wr);
|
||||
}
|
||||
}
|
||||
|
||||
// *****************************************************************************
|
||||
// send data down the local comm port
|
||||
|
||||
void apiconfig_processRx(void)
|
||||
{
|
||||
if (apiconfig_tx_config_buffer_wr > 0)
|
||||
{ // send any config packets in the config buffer
|
||||
|
||||
while (TRUE)
|
||||
{
|
||||
uint16_t data_size = apiconfig_tx_config_buffer_wr;
|
||||
|
||||
// if (data_size > 32)
|
||||
// data_size = 32;
|
||||
|
||||
if (!apiconfig_usb_comms && !GPIO_IN(SERIAL_CTS_PIN))
|
||||
break; // we can't yet send data down the comm-port
|
||||
|
||||
// send the data out the comm-port
|
||||
int32_t res = PIOS_COM_SendBufferNonBlocking(apiconfig_comm_port, apiconfig_tx_config_buffer, data_size);
|
||||
if (res < 0)
|
||||
{ // failed to send the data out the comm-port
|
||||
|
||||
#if defined(APICONFIG_DEBUG)
|
||||
DEBUG_PRINTF("PIOS_COM_SendBuffer %d %d\r\n", data_size, res);
|
||||
#endif
|
||||
|
||||
if (apiconfig_tx_timer >= 5000)
|
||||
{ // seems we can't send our data for at least the last 5 seconds - delete it
|
||||
apiconfig_tx_config_buffer_wr = 0;
|
||||
}
|
||||
|
||||
break;
|
||||
}
|
||||
|
||||
// data was sent out the comm-port OK .. remove the sent data from our buffer
|
||||
|
||||
#if defined(APICONFIG_DEBUG)
|
||||
DEBUG_PRINTF("TX api config: data [%u]\r\n", data_size);
|
||||
#endif
|
||||
|
||||
apiconfig_tx_config_buffer_wr -= data_size;
|
||||
if (apiconfig_tx_config_buffer_wr > 0)
|
||||
memmove(apiconfig_tx_config_buffer, apiconfig_tx_config_buffer + data_size, apiconfig_tx_config_buffer_wr);
|
||||
|
||||
apiconfig_tx_timer = 0;
|
||||
|
||||
break;
|
||||
}
|
||||
|
||||
return;
|
||||
}
|
||||
|
||||
if (saved_settings.mode == MODE_NORMAL || saved_settings.mode == MODE_STREAM_RX)
|
||||
{
|
||||
// send the data received via the RF link out the comm-port
|
||||
while (TRUE)
|
||||
{
|
||||
// get number of data bytes received via the RF link
|
||||
uint16_t ph_num = ph_getData_used(apiconfig_connection_index);
|
||||
|
||||
// limit to how much space we have in the temp TX buffer
|
||||
if (ph_num > sizeof(apiconfig_tx_buffer) - apiconfig_tx_buffer_wr)
|
||||
ph_num = sizeof(apiconfig_tx_buffer) - apiconfig_tx_buffer_wr;
|
||||
|
||||
if (ph_num > 0)
|
||||
{ // fetch the data bytes received via the RF link and save into our temp buffer
|
||||
ph_num = ph_getData(apiconfig_connection_index, apiconfig_tx_buffer + apiconfig_tx_buffer_wr, ph_num);
|
||||
apiconfig_tx_buffer_wr += ph_num;
|
||||
}
|
||||
|
||||
uint16_t data_size = apiconfig_tx_buffer_wr;
|
||||
if (data_size == 0)
|
||||
break; // no data to send
|
||||
|
||||
// we have data to send down the comm-port
|
||||
/*
|
||||
#if (defined(PIOS_COM_DEBUG) && (PIOS_COM_DEBUG == PIOS_COM_SERIAL))
|
||||
if (!apiconfig_usb_comms)
|
||||
{ // the serial-port is being used for debugging - don't send data down it
|
||||
apiconfig_tx_buffer_wr = 0;
|
||||
apiconfig_tx_timer = 0;
|
||||
continue;
|
||||
}
|
||||
#endif
|
||||
*/
|
||||
if (!apiconfig_usb_comms && !GPIO_IN(SERIAL_CTS_PIN))
|
||||
break; // we can't yet send data down the comm-port
|
||||
|
||||
// send the data out the comm-port
|
||||
int32_t res = PIOS_COM_SendBufferNonBlocking(apiconfig_comm_port, apiconfig_tx_buffer, data_size);
|
||||
if (res < 0)
|
||||
{ // failed to send the data out the comm-port
|
||||
|
||||
#if defined(APICONFIG_DEBUG)
|
||||
DEBUG_PRINTF("PIOS_COM_SendBuffer %d %d\r\n", data_size, res);
|
||||
#endif
|
||||
|
||||
if (apiconfig_tx_timer >= 5000)
|
||||
{ // seems we can't send our data for at least the last 5 seconds - delete it
|
||||
apiconfig_tx_buffer_wr = 0;
|
||||
}
|
||||
|
||||
break;
|
||||
}
|
||||
|
||||
// data was sent out the comm-port OK .. remove the sent data from our buffer
|
||||
|
||||
apiconfig_tx_buffer_wr -= data_size;
|
||||
if (apiconfig_tx_buffer_wr > 0)
|
||||
memmove(apiconfig_tx_buffer, apiconfig_tx_buffer + data_size, apiconfig_tx_buffer_wr);
|
||||
|
||||
apiconfig_tx_timer = 0;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// *************************************************************
|
||||
|
||||
void apiconfig_process_scan_spectrum(void)
|
||||
{
|
||||
if (saved_settings.mode != MODE_SCAN_SPECTRUM)
|
||||
return;
|
||||
|
||||
if (apiconfig_ss_timer < 1) return; // 1ms
|
||||
apiconfig_ss_timer = 0;
|
||||
|
||||
if (++led_counter >= 30)
|
||||
{
|
||||
led_counter = 0;
|
||||
// RX_LED_TOGGLE;
|
||||
LINK_LED_TOGGLE;
|
||||
}
|
||||
|
||||
// uint16_t freq_step_size = (uint16_t)(rfm22_getFrequencyStepSize() * 4 + 0.5f);
|
||||
uint16_t freq_step_size = (uint16_t)(rfm22_getFrequencyStepSize() * 20 + 0.5f);
|
||||
|
||||
// fetch the current rssi level
|
||||
int16_t rssi_dbm = rfm22_getRSSI();
|
||||
if (rssi_dbm < -128) rssi_dbm = -128;
|
||||
else
|
||||
if (rssi_dbm > 0) rssi_dbm = 0;
|
||||
|
||||
// onto next frequency
|
||||
apiconfig_spec_freq += freq_step_size;
|
||||
if (apiconfig_spec_freq >= rfm22_maxFrequency()) apiconfig_spec_freq = rfm22_minFrequency();
|
||||
rfm22_setNominalCarrierFrequency(apiconfig_spec_freq);
|
||||
// rfm22_setRxMode(RX_SCAN_SPECTRUM, true);
|
||||
|
||||
// add the RSSI value to the buffer
|
||||
apiconfig_spec_buffer[apiconfig_spec_buffer_wr] = rssi_dbm;
|
||||
if (++apiconfig_spec_buffer_wr >= sizeof(apiconfig_spec_buffer))
|
||||
{ // send the buffer
|
||||
apiconfig_sendSpectrumPacket(apiconfig_spec_start_freq, freq_step_size, apiconfig_spec_buffer, apiconfig_spec_buffer_wr);
|
||||
|
||||
apiconfig_spec_buffer_wr = 0;
|
||||
apiconfig_spec_start_freq = apiconfig_spec_freq;
|
||||
}
|
||||
}
|
||||
|
||||
// *****************************************************************************
|
||||
// call this as often as possible - not from an interrupt
|
||||
|
||||
void apiconfig_process(void)
|
||||
{ // copy data from comm-port RX buffer to RF packet handler TX buffer, and from RF packet handler RX buffer to comm-port TX buffer
|
||||
|
||||
apiconfig_process_scan_spectrum();
|
||||
|
||||
// ********************
|
||||
|
||||
// decide which comm-port we are using (usart or usb)
|
||||
apiconfig_usb_comms = false; // TRUE if we are using the usb port for comms.
|
||||
apiconfig_comm_port = PIOS_COM_SERIAL; // default to using the usart comm-port
|
||||
#if defined(PIOS_INCLUDE_USB)
|
||||
if (PIOS_USB_CheckAvailable(0))
|
||||
{ // USB comms is up, use the USB comm-port instead of the USART comm-port
|
||||
apiconfig_usb_comms = true;
|
||||
apiconfig_comm_port = PIOS_COM_TELEM_USB;
|
||||
}
|
||||
#endif
|
||||
|
||||
// check to see if the local communication port has changed (usart/usb)
|
||||
if (apiconfig_previous_com_port == 0 && apiconfig_previous_com_port != apiconfig_comm_port)
|
||||
{ // the local communications port has changed .. remove any data in the buffers
|
||||
apiconfig_rx_buffer_wr = 0;
|
||||
apiconfig_tx_buffer_wr = 0;
|
||||
apiconfig_tx_config_buffer_wr = 0;
|
||||
}
|
||||
else
|
||||
if (apiconfig_usb_comms)
|
||||
{ // we're using the USB for comms - keep the USART rx buffer empty
|
||||
uint8_t c;
|
||||
while (PIOS_COM_ReceiveBuffer(PIOS_COM_SERIAL, &c, 1, 0) > 0);
|
||||
}
|
||||
apiconfig_previous_com_port = apiconfig_comm_port; // remember the current comm-port we are using
|
||||
|
||||
apiconfig_connection_index = 0; // the RF connection we are using
|
||||
|
||||
// *******************
|
||||
// fetch the data received via the comm-port
|
||||
|
||||
// get the number of data bytes received down the comm-port
|
||||
uint16_t buf_avail = sizeof(apiconfig_rx_buffer) - apiconfig_rx_buffer_wr;
|
||||
|
||||
PIOS_COM_ReceiveBuffer(apiconfig_comm_port, &(apiconfig_rx_buffer[apiconfig_rx_buffer_wr]), buf_avail, 0);
|
||||
|
||||
apiconfig_processTx();
|
||||
apiconfig_processRx();
|
||||
|
||||
// speed the pinging speed up if the GCS is connected and monitoring the signal level etc
|
||||
ph_setFastPing(apiconfig_rx_config_timer < 2000);
|
||||
}
|
||||
|
||||
// *****************************************************************************
|
||||
// can be called from an interrupt if you wish
|
||||
|
||||
void apiconfig_1ms_tick(void)
|
||||
{ // call this once every 1ms
|
||||
|
||||
if (apiconfig_rx_config_timer < 0xffff) apiconfig_rx_config_timer++;
|
||||
if (apiconfig_rx_timer < 0xffff) apiconfig_rx_timer++;
|
||||
if (apiconfig_tx_timer < 0xffff) apiconfig_tx_timer++;
|
||||
if (apiconfig_ss_timer < 0xffff) apiconfig_ss_timer++;
|
||||
}
|
||||
|
||||
// *****************************************************************************
|
||||
|
||||
void apiconfig_init(void)
|
||||
{
|
||||
apiconfig_previous_com_port = 0;
|
||||
|
||||
apiconfig_rx_buffer_wr = 0;
|
||||
|
||||
apiconfig_tx_buffer_wr = 0;
|
||||
|
||||
apiconfig_tx_config_buffer_wr = 0;
|
||||
|
||||
apiconfig_rx_config_timer = 0xffff;
|
||||
apiconfig_rx_timer = 0;
|
||||
apiconfig_tx_timer = 0;
|
||||
apiconfig_ss_timer = 0;
|
||||
|
||||
apiconfig_spec_buffer_wr = 0;
|
||||
apiconfig_spec_start_freq = 0;
|
||||
|
||||
led_counter = 0;
|
||||
}
|
||||
|
||||
// *****************************************************************************
|
@ -1,189 +0,0 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file crc.c
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @brief Serial communication port handling routines
|
||||
* @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 "crc.h"
|
||||
|
||||
// **************************************************************************
|
||||
|
||||
#define Poly16 0x8408 // HDLC polynomial: 1 + x**5 + x**12 + x**16
|
||||
#define Poly32 0x04c11db7 // 32-bit polynomial .. this should produce the same as the STM32 hardware CRC
|
||||
|
||||
static const uint16_t CRC_Table16[] = { // HDLC polynomial
|
||||
0x0000, 0x1189, 0x2312, 0x329b, 0x4624, 0x57ad, 0x6536, 0x74bf,
|
||||
0x8c48, 0x9dc1, 0xaf5a, 0xbed3, 0xca6c, 0xdbe5, 0xe97e, 0xf8f7,
|
||||
0x1081, 0x0108, 0x3393, 0x221a, 0x56a5, 0x472c, 0x75b7, 0x643e,
|
||||
0x9cc9, 0x8d40, 0xbfdb, 0xae52, 0xdaed, 0xcb64, 0xf9ff, 0xe876,
|
||||
0x2102, 0x308b, 0x0210, 0x1399, 0x6726, 0x76af, 0x4434, 0x55bd,
|
||||
0xad4a, 0xbcc3, 0x8e58, 0x9fd1, 0xeb6e, 0xfae7, 0xc87c, 0xd9f5,
|
||||
0x3183, 0x200a, 0x1291, 0x0318, 0x77a7, 0x662e, 0x54b5, 0x453c,
|
||||
0xbdcb, 0xac42, 0x9ed9, 0x8f50, 0xfbef, 0xea66, 0xd8fd, 0xc974,
|
||||
0x4204, 0x538d, 0x6116, 0x709f, 0x0420, 0x15a9, 0x2732, 0x36bb,
|
||||
0xce4c, 0xdfc5, 0xed5e, 0xfcd7, 0x8868, 0x99e1, 0xab7a, 0xbaf3,
|
||||
0x5285, 0x430c, 0x7197, 0x601e, 0x14a1, 0x0528, 0x37b3, 0x263a,
|
||||
0xdecd, 0xcf44, 0xfddf, 0xec56, 0x98e9, 0x8960, 0xbbfb, 0xaa72,
|
||||
0x6306, 0x728f, 0x4014, 0x519d, 0x2522, 0x34ab, 0x0630, 0x17b9,
|
||||
0xef4e, 0xfec7, 0xcc5c, 0xddd5, 0xa96a, 0xb8e3, 0x8a78, 0x9bf1,
|
||||
0x7387, 0x620e, 0x5095, 0x411c, 0x35a3, 0x242a, 0x16b1, 0x0738,
|
||||
0xffcf, 0xee46, 0xdcdd, 0xcd54, 0xb9eb, 0xa862, 0x9af9, 0x8b70,
|
||||
0x8408, 0x9581, 0xa71a, 0xb693, 0xc22c, 0xd3a5, 0xe13e, 0xf0b7,
|
||||
0x0840, 0x19c9, 0x2b52, 0x3adb, 0x4e64, 0x5fed, 0x6d76, 0x7cff,
|
||||
0x9489, 0x8500, 0xb79b, 0xa612, 0xd2ad, 0xc324, 0xf1bf, 0xe036,
|
||||
0x18c1, 0x0948, 0x3bd3, 0x2a5a, 0x5ee5, 0x4f6c, 0x7df7, 0x6c7e,
|
||||
0xa50a, 0xb483, 0x8618, 0x9791, 0xe32e, 0xf2a7, 0xc03c, 0xd1b5,
|
||||
0x2942, 0x38cb, 0x0a50, 0x1bd9, 0x6f66, 0x7eef, 0x4c74, 0x5dfd,
|
||||
0xb58b, 0xa402, 0x9699, 0x8710, 0xf3af, 0xe226, 0xd0bd, 0xc134,
|
||||
0x39c3, 0x284a, 0x1ad1, 0x0b58, 0x7fe7, 0x6e6e, 0x5cf5, 0x4d7c,
|
||||
0xc60c, 0xd785, 0xe51e, 0xf497, 0x8028, 0x91a1, 0xa33a, 0xb2b3,
|
||||
0x4a44, 0x5bcd, 0x6956, 0x78df, 0x0c60, 0x1de9, 0x2f72, 0x3efb,
|
||||
0xd68d, 0xc704, 0xf59f, 0xe416, 0x90a9, 0x8120, 0xb3bb, 0xa232,
|
||||
0x5ac5, 0x4b4c, 0x79d7, 0x685e, 0x1ce1, 0x0d68, 0x3ff3, 0x2e7a,
|
||||
0xe70e, 0xf687, 0xc41c, 0xd595, 0xa12a, 0xb0a3, 0x8238, 0x93b1,
|
||||
0x6b46, 0x7acf, 0x4854, 0x59dd, 0x2d62, 0x3ceb, 0x0e70, 0x1ff9,
|
||||
0xf78f, 0xe606, 0xd49d, 0xc514, 0xb1ab, 0xa022, 0x92b9, 0x8330,
|
||||
0x7bc7, 0x6a4e, 0x58d5, 0x495c, 0x3de3, 0x2c6a, 0x1ef1, 0x0f78
|
||||
};
|
||||
|
||||
static const uint32_t CRC_Table32[] = {
|
||||
0x00000000, 0x04c11db7, 0x09823b6e, 0x0d4326d9, 0x130476dc, 0x17c56b6b, 0x1a864db2, 0x1e475005,
|
||||
0x2608edb8, 0x22c9f00f, 0x2f8ad6d6, 0x2b4bcb61, 0x350c9b64, 0x31cd86d3, 0x3c8ea00a, 0x384fbdbd,
|
||||
0x4c11db70, 0x48d0c6c7, 0x4593e01e, 0x4152fda9, 0x5f15adac, 0x5bd4b01b, 0x569796c2, 0x52568b75,
|
||||
0x6a1936c8, 0x6ed82b7f, 0x639b0da6, 0x675a1011, 0x791d4014, 0x7ddc5da3, 0x709f7b7a, 0x745e66cd,
|
||||
0x9823b6e0, 0x9ce2ab57, 0x91a18d8e, 0x95609039, 0x8b27c03c, 0x8fe6dd8b, 0x82a5fb52, 0x8664e6e5,
|
||||
0xbe2b5b58, 0xbaea46ef, 0xb7a96036, 0xb3687d81, 0xad2f2d84, 0xa9ee3033, 0xa4ad16ea, 0xa06c0b5d,
|
||||
0xd4326d90, 0xd0f37027, 0xddb056fe, 0xd9714b49, 0xc7361b4c, 0xc3f706fb, 0xceb42022, 0xca753d95,
|
||||
0xf23a8028, 0xf6fb9d9f, 0xfbb8bb46, 0xff79a6f1, 0xe13ef6f4, 0xe5ffeb43, 0xe8bccd9a, 0xec7dd02d,
|
||||
0x34867077, 0x30476dc0, 0x3d044b19, 0x39c556ae, 0x278206ab, 0x23431b1c, 0x2e003dc5, 0x2ac12072,
|
||||
0x128e9dcf, 0x164f8078, 0x1b0ca6a1, 0x1fcdbb16, 0x018aeb13, 0x054bf6a4, 0x0808d07d, 0x0cc9cdca,
|
||||
0x7897ab07, 0x7c56b6b0, 0x71159069, 0x75d48dde, 0x6b93dddb, 0x6f52c06c, 0x6211e6b5, 0x66d0fb02,
|
||||
0x5e9f46bf, 0x5a5e5b08, 0x571d7dd1, 0x53dc6066, 0x4d9b3063, 0x495a2dd4, 0x44190b0d, 0x40d816ba,
|
||||
0xaca5c697, 0xa864db20, 0xa527fdf9, 0xa1e6e04e, 0xbfa1b04b, 0xbb60adfc, 0xb6238b25, 0xb2e29692,
|
||||
0x8aad2b2f, 0x8e6c3698, 0x832f1041, 0x87ee0df6, 0x99a95df3, 0x9d684044, 0x902b669d, 0x94ea7b2a,
|
||||
0xe0b41de7, 0xe4750050, 0xe9362689, 0xedf73b3e, 0xf3b06b3b, 0xf771768c, 0xfa325055, 0xfef34de2,
|
||||
0xc6bcf05f, 0xc27dede8, 0xcf3ecb31, 0xcbffd686, 0xd5b88683, 0xd1799b34, 0xdc3abded, 0xd8fba05a,
|
||||
0x690ce0ee, 0x6dcdfd59, 0x608edb80, 0x644fc637, 0x7a089632, 0x7ec98b85, 0x738aad5c, 0x774bb0eb,
|
||||
0x4f040d56, 0x4bc510e1, 0x46863638, 0x42472b8f, 0x5c007b8a, 0x58c1663d, 0x558240e4, 0x51435d53,
|
||||
0x251d3b9e, 0x21dc2629, 0x2c9f00f0, 0x285e1d47, 0x36194d42, 0x32d850f5, 0x3f9b762c, 0x3b5a6b9b,
|
||||
0x0315d626, 0x07d4cb91, 0x0a97ed48, 0x0e56f0ff, 0x1011a0fa, 0x14d0bd4d, 0x19939b94, 0x1d528623,
|
||||
0xf12f560e, 0xf5ee4bb9, 0xf8ad6d60, 0xfc6c70d7, 0xe22b20d2, 0xe6ea3d65, 0xeba91bbc, 0xef68060b,
|
||||
0xd727bbb6, 0xd3e6a601, 0xdea580d8, 0xda649d6f, 0xc423cd6a, 0xc0e2d0dd, 0xcda1f604, 0xc960ebb3,
|
||||
0xbd3e8d7e, 0xb9ff90c9, 0xb4bcb610, 0xb07daba7, 0xae3afba2, 0xaafbe615, 0xa7b8c0cc, 0xa379dd7b,
|
||||
0x9b3660c6, 0x9ff77d71, 0x92b45ba8, 0x9675461f, 0x8832161a, 0x8cf30bad, 0x81b02d74, 0x857130c3,
|
||||
0x5d8a9099, 0x594b8d2e, 0x5408abf7, 0x50c9b640, 0x4e8ee645, 0x4a4ffbf2, 0x470cdd2b, 0x43cdc09c,
|
||||
0x7b827d21, 0x7f436096, 0x7200464f, 0x76c15bf8, 0x68860bfd, 0x6c47164a, 0x61043093, 0x65c52d24,
|
||||
0x119b4be9, 0x155a565e, 0x18197087, 0x1cd86d30, 0x029f3d35, 0x065e2082, 0x0b1d065b, 0x0fdc1bec,
|
||||
0x3793a651, 0x3352bbe6, 0x3e119d3f, 0x3ad08088, 0x2497d08d, 0x2056cd3a, 0x2d15ebe3, 0x29d4f654,
|
||||
0xc5a92679, 0xc1683bce, 0xcc2b1d17, 0xc8ea00a0, 0xd6ad50a5, 0xd26c4d12, 0xdf2f6bcb, 0xdbee767c,
|
||||
0xe3a1cbc1, 0xe760d676, 0xea23f0af, 0xeee2ed18, 0xf0a5bd1d, 0xf464a0aa, 0xf9278673, 0xfde69bc4,
|
||||
0x89b8fd09, 0x8d79e0be, 0x803ac667, 0x84fbdbd0, 0x9abc8bd5, 0x9e7d9662, 0x933eb0bb, 0x97ffad0c,
|
||||
0xafb010b1, 0xab710d06, 0xa6322bdf, 0xa2f33668, 0xbcb4666d, 0xb8757bda, 0xb5365d03, 0xb1f740b4
|
||||
};
|
||||
|
||||
// **************************************************************************
|
||||
// 16-bit CRC
|
||||
|
||||
inline uint16_t updateCRC16(uint16_t crc, uint8_t b)
|
||||
{ // update the crc - table method
|
||||
return ((crc >> 8) ^ CRC_Table16[(crc & 0xff) ^ b]);
|
||||
}
|
||||
/*
|
||||
uint16_t updateCRC16(uint16_t crc, uint8_t b)
|
||||
{ // update the fcs - bit band method
|
||||
register uint8_t f = (uint8_t)(crc >> 8);
|
||||
crc = (crc & 0x00ff) ^ b;
|
||||
for (int i = 8; i > 0; i--)
|
||||
crc = (crc & 1) ? (crc >> 1) ^ Poly16 : crc >> 1;
|
||||
return (crc ^ f);
|
||||
}
|
||||
*/
|
||||
uint16_t updateCRC16Data(uint16_t crc, void *data, uint32_t len)
|
||||
{
|
||||
register uint8_t *p = (uint8_t *)data;
|
||||
register uint16_t _crc = crc;
|
||||
for (register uint32_t i = len; i > 0; i--)
|
||||
_crc = (_crc >> 8) ^ CRC_Table16[(_crc ^ *p++) & 0xff];
|
||||
// _crc = UpdateCRC16(_crc, *p++);
|
||||
return _crc;
|
||||
}
|
||||
/*
|
||||
// Generate the CRC table
|
||||
void makeCRC_Table16(void)
|
||||
{
|
||||
for (uint16_t i = 0; i < 256; i++)
|
||||
{
|
||||
uint16_t crc = i;
|
||||
for (int j = 8; j > 0; j--)
|
||||
crc = (crc & 1) ? (crc >> 1) ^ Poly16 : crc >> 1;
|
||||
CRC_Table16[i] = crc;
|
||||
}
|
||||
}
|
||||
*/
|
||||
// **************************************************************************
|
||||
// 32-bit CRC
|
||||
|
||||
inline uint32_t updateCRC32(uint32_t crc, uint8_t b)
|
||||
{
|
||||
return ((crc << 8) ^ CRC_Table32[(crc >> 24) ^ b]);
|
||||
}
|
||||
/*
|
||||
uint32_t updateCRC32(uint32_t crc, uint8_t b)
|
||||
{ // update the crc - bit bang method
|
||||
register uint32_t f = crc << 8;
|
||||
crc = (crc >> 24) ^ b;
|
||||
for (int i = 8; i > 0; i--)
|
||||
crc = (crc & 1) ? (crc << 1) ^ Poly32 : crc << 1;
|
||||
return (crc ^ f);
|
||||
}
|
||||
*/
|
||||
uint32_t updateCRC32Data(uint32_t crc, void *data, uint32_t len)
|
||||
{
|
||||
register uint8_t *p = (uint8_t *)data;
|
||||
register uint32_t _crc = crc;
|
||||
for (register uint32_t i = len; i > 0; i--)
|
||||
_crc = (_crc << 8) ^ CRC_Table32[(_crc >> 24) ^ *p++];
|
||||
// _crc = UpdateCRC32(_crc, *p++);
|
||||
return _crc;
|
||||
}
|
||||
/*
|
||||
// Generate the CRC table
|
||||
void makeCRC_Table32(void)
|
||||
{
|
||||
for (uint32_t i = 0; i < 256; i++)
|
||||
{
|
||||
uint32_t crc = i;
|
||||
for (int j = 8; j > 0; j--)
|
||||
crc = (crc & 1) ? (crc << 1) ^ Poly32 : crc << 1;
|
||||
CRC_Table32[i] = crc;
|
||||
}
|
||||
}
|
||||
*/
|
||||
// **************************************************************************
|
||||
|
||||
void CRC_init(void)
|
||||
{
|
||||
// MakeCRC_Table16();
|
||||
// MakeCRC_Table32();
|
||||
}
|
||||
|
||||
// **************************************************************************
|
@ -1,182 +0,0 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file gpio_in.c
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @brief GPIO input functions
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
*
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* This program is free software; you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation; either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful, but
|
||||
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
|
||||
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
|
||||
* for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License along
|
||||
* with this program; if not, write to the Free Software Foundation, Inc.,
|
||||
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
*/
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
/* *****************************************************************
|
||||
// Example pin definitions .. this would go into your pios_board.h file
|
||||
|
||||
// GPIO_Mode_AIN Analog Input
|
||||
// GPIO_Mode_IN_FLOATING Input Floating
|
||||
// GPIO_Mode_IPD Input Pull-Down
|
||||
// GPIO_Mode_IPU Input Pull-up
|
||||
|
||||
// API mode line
|
||||
#define GPIO_IN_0_PORT GPIOB
|
||||
#define GPIO_IN_0_PIN GPIO_Pin_13
|
||||
#define GPIO_IN_0_MODE GPIO_Mode_IPU
|
||||
|
||||
// Serial port CTS line
|
||||
#define GPIO_IN_1_PORT GPIOB
|
||||
#define GPIO_IN_1_PIN GPIO_Pin_14
|
||||
#define GPIO_IN_1_MODE GPIO_Mode_IPU
|
||||
|
||||
#define GPIO_IN_NUM 2
|
||||
#define GPIO_IN_PORTS { GPIO_IN_0_PORT, GPIO_IN_1_PORT }
|
||||
#define GPIO_IN_PINS { GPIO_IN_0_PIN, GPIO_IN_1_PIN }
|
||||
#define GPIO_IN_MODES { GPIO_IN_0_MODE, GPIO_IN_1_MODE }
|
||||
|
||||
#define API_MODE_PIN 0
|
||||
#define SERIAL_CTS_PIN 1
|
||||
|
||||
*********************************************************************
|
||||
Example usage ..
|
||||
|
||||
{
|
||||
|
||||
|
||||
|
||||
// setup all the GPIO input pins
|
||||
GPIO_IN_Init();
|
||||
|
||||
|
||||
|
||||
|
||||
if (!GPIO_IN(API_MODE_PIN))
|
||||
{ // pin is LOW
|
||||
|
||||
|
||||
}
|
||||
else
|
||||
{ // pin is HIGH
|
||||
|
||||
|
||||
}
|
||||
|
||||
|
||||
|
||||
}
|
||||
|
||||
***************************************************************************** */
|
||||
|
||||
|
||||
|
||||
|
||||
#include <pios.h>
|
||||
|
||||
#include "gpio_in.h"
|
||||
|
||||
// *****************************************************************************
|
||||
// setup the GPIO input pins
|
||||
|
||||
// PORT ..
|
||||
// GPIOA
|
||||
// GPIOB
|
||||
// GPIOC
|
||||
// GPIOD
|
||||
// GPIOE
|
||||
// GPIOF
|
||||
// GPIOG
|
||||
|
||||
// PIN ..
|
||||
// GPIO_Pin_0
|
||||
// GPIO_Pin_1
|
||||
// GPIO_Pin_2
|
||||
// GPIO_Pin_3
|
||||
// GPIO_Pin_4
|
||||
// GPIO_Pin_5
|
||||
// GPIO_Pin_6
|
||||
// GPIO_Pin_7
|
||||
// GPIO_Pin_8
|
||||
// GPIO_Pin_9
|
||||
// GPIO_Pin_10
|
||||
// GPIO_Pin_11
|
||||
// GPIO_Pin_12
|
||||
// GPIO_Pin_13
|
||||
// GPIO_Pin_14
|
||||
// GPIO_Pin_15
|
||||
|
||||
// MODE ..
|
||||
// GPIO_Mode_AIN Analog Input
|
||||
// GPIO_Mode_IN_FLOATING Input Floating
|
||||
// GPIO_Mode_IPD Input Pull-Down
|
||||
// GPIO_Mode_IPU Input Pull-up
|
||||
|
||||
#if defined(GPIO_IN_NUM) && defined(GPIO_IN_PORTS) && defined(GPIO_IN_PINS) && defined(GPIO_IN_MODES)
|
||||
// #if defined(PIOS_INCLUDE_GPIO_IN) && defined(PIOS_GPIO_IN_NUM) && defined(PIOS_GPIO_IN_PORTS) && defined(PIOS_GPIO_IN_PINS) && defined(PIOS_GPIO_IN_MODES)
|
||||
|
||||
// Local Variables
|
||||
static GPIO_TypeDef *GPIO_IN_PORT[GPIO_IN_NUM] = GPIO_IN_PORTS;
|
||||
static const uint32_t GPIO_IN_PIN[GPIO_IN_NUM] = GPIO_IN_PINS;
|
||||
static const uint32_t GPIO_IN_MODE[GPIO_IN_NUM] = GPIO_IN_MODES;
|
||||
|
||||
/**
|
||||
* Initialises all the GPIO INPUT's
|
||||
*/
|
||||
void GPIO_IN_Init(void)
|
||||
{
|
||||
GPIO_InitTypeDef GPIO_InitStructure;
|
||||
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_2MHz;
|
||||
|
||||
for (int i = 0; i < GPIO_IN_NUM; i++)
|
||||
{
|
||||
switch ((uint32_t)GPIO_IN_PORT[i])
|
||||
{
|
||||
case (uint32_t)GPIOA: RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOA, ENABLE); break;
|
||||
case (uint32_t)GPIOB: RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOB, ENABLE); break;
|
||||
case (uint32_t)GPIOC: RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOC, ENABLE); break;
|
||||
case (uint32_t)GPIOD: RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOD, ENABLE); break;
|
||||
case (uint32_t)GPIOE: RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOE, ENABLE); break;
|
||||
case (uint32_t)GPIOF: RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOF, ENABLE); break;
|
||||
case (uint32_t)GPIOG: RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOG, ENABLE); break;
|
||||
}
|
||||
GPIO_InitStructure.GPIO_Pin = GPIO_IN_PIN[i];
|
||||
GPIO_InitStructure.GPIO_Mode = GPIO_IN_MODE[i];
|
||||
GPIO_Init(GPIO_IN_PORT[i], &GPIO_InitStructure);
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Read input pin level
|
||||
* \param[num] Pin Pin Number
|
||||
*/
|
||||
bool GPIO_IN(uint8_t num)
|
||||
{ // return ..
|
||||
// FALSE if the input pin is LOW
|
||||
// TRUE if the input pin is HIGH
|
||||
if (num >= GPIO_IN_NUM) return FALSE;
|
||||
return ((GPIO_IN_PORT[num]->IDR & GPIO_IN_PIN[num]) != 0);
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
// ***********************************************************************************
|
||||
|
||||
/**
|
||||
* @}
|
||||
* @}
|
||||
*/
|
@ -1,74 +0,0 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file main.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @brief Main modem 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 __MAIN_H__
|
||||
#define __MAIN_H__
|
||||
|
||||
#include <pios.h>
|
||||
|
||||
// *****************************************************************************
|
||||
|
||||
// firmware version
|
||||
#define VERSION_MAJOR 0 // 0 to 255
|
||||
#define VERSION_MINOR 9 // 0 to 255
|
||||
|
||||
// macro's for reading internal flash memory
|
||||
#define mem8(addr) (*((volatile uint8_t *)(addr)))
|
||||
#define mem16(addr) (*((volatile uint16_t *)(addr)))
|
||||
#define mem32(addr) (*((volatile uint32_t *)(addr)))
|
||||
|
||||
enum {
|
||||
FREQBAND_UNKNOWN = 0,
|
||||
FREQBAND_434MHz,
|
||||
FREQBAND_868MHz,
|
||||
FREQBAND_915MHz
|
||||
};
|
||||
|
||||
enum {
|
||||
MODE_NORMAL = 0, // normal 2-way packet mode
|
||||
MODE_STREAM_TX, // 1-way continuous tx packet mode
|
||||
MODE_STREAM_RX, // 1-way continuous rx packet mode
|
||||
MODE_PPM_TX, // PPM tx mode
|
||||
MODE_PPM_RX, // PPM rx mode
|
||||
MODE_SCAN_SPECTRUM, // scan the receiver over the whole band
|
||||
MODE_TX_BLANK_CARRIER_TEST, // blank carrier Tx mode (for calibrating the carrier frequency say)
|
||||
MODE_TX_SPECTRUM_TEST // pseudo random Tx data mode (for checking the Tx carrier spectrum)
|
||||
};
|
||||
|
||||
// *****************************************************************************
|
||||
|
||||
extern volatile uint32_t random32;
|
||||
|
||||
extern bool booting;
|
||||
|
||||
extern uint32_t flash_size;
|
||||
|
||||
extern char serial_number_str[25];
|
||||
extern uint32_t serial_number_crc32;
|
||||
|
||||
// *****************************************************************************
|
||||
|
||||
#endif
|
@ -1,76 +0,0 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file packet_handler.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @brief Modem packet handling routines
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
*
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* This program is free software; you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation; either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful, but
|
||||
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
|
||||
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
|
||||
* for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License along
|
||||
* with this program; if not, write to the Free Software Foundation, Inc.,
|
||||
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
*/
|
||||
|
||||
#ifndef __PACKET_HANDLER_H__
|
||||
#define __PACKET_HANDLER_H__
|
||||
|
||||
#include "stdint.h"
|
||||
|
||||
// *****************************************************************************
|
||||
|
||||
#define PH_MAX_CONNECTIONS 1 // maximum number of remote connections
|
||||
|
||||
// *****************************************************************************
|
||||
|
||||
void ph_1ms_tick(void);
|
||||
void ph_process(void);
|
||||
|
||||
bool ph_connected(const int connection_index);
|
||||
|
||||
uint16_t ph_putData_free(const int connection_index);
|
||||
uint16_t ph_putData(const int connection_index, const void *data, uint16_t len);
|
||||
|
||||
uint16_t ph_getData_used(const int connection_index);
|
||||
uint16_t ph_getData(const int connection_index, void *data, uint16_t len);
|
||||
|
||||
void ph_setFastPing(bool fast);
|
||||
|
||||
uint16_t ph_getRetries(const int connection_index);
|
||||
|
||||
uint8_t ph_getCurrentLinkState(const int connection_index);
|
||||
|
||||
int16_t ph_getLastRSSI(const int connection_index);
|
||||
int32_t ph_getLastAFC(const int connection_index);
|
||||
|
||||
void ph_setNominalCarrierFrequency(uint32_t frequency_hz);
|
||||
uint32_t ph_getNominalCarrierFrequency(void);
|
||||
|
||||
void ph_setDatarate(uint32_t datarate_bps);
|
||||
uint32_t ph_getDatarate(void);
|
||||
|
||||
void ph_setTxPower(uint8_t tx_power);
|
||||
uint8_t ph_getTxPower(void);
|
||||
|
||||
void ph_set_AES128_key(const void *key);
|
||||
|
||||
int ph_set_remote_serial_number(int connection_index, uint32_t sn);
|
||||
void ph_set_remote_encryption(int connection_index, bool enabled, const void *key);
|
||||
|
||||
void ph_deinit(void);
|
||||
void ph_init(uint32_t our_sn);
|
||||
|
||||
// *****************************************************************************
|
||||
|
||||
#endif
|
@ -1,80 +0,0 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file saved_settings.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @brief RF Module hardware layer
|
||||
* @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 _SAVED_SETTINGS_H_
|
||||
#define _SAVED_SETTINGS_H_
|
||||
|
||||
// *****************************************************************
|
||||
|
||||
#include "stm32f10x.h"
|
||||
#include "stm32f10x_flash.h"
|
||||
|
||||
// *****************************************************************
|
||||
|
||||
typedef struct
|
||||
{
|
||||
uint32_t serial_baudrate; // serial uart baudrate
|
||||
|
||||
uint32_t destination_id;
|
||||
|
||||
uint32_t min_frequency_Hz;
|
||||
uint32_t max_frequency_Hz;
|
||||
uint32_t frequency_Hz;
|
||||
|
||||
uint32_t max_rf_bandwidth;
|
||||
|
||||
uint8_t max_tx_power;
|
||||
|
||||
uint8_t frequency_band;
|
||||
|
||||
uint8_t rf_xtal_cap;
|
||||
|
||||
bool aes_enable;
|
||||
uint8_t aes_key[16];
|
||||
|
||||
uint8_t mode;
|
||||
|
||||
uint8_t rts_time;
|
||||
|
||||
uint8_t spare[30]; // allow for future unknown settings
|
||||
|
||||
uint32_t crc;
|
||||
} __attribute__((__packed__)) t_saved_settings;
|
||||
|
||||
// *****************************************************************
|
||||
// public variables
|
||||
|
||||
extern volatile t_saved_settings saved_settings __attribute__ ((aligned(4))); // a RAM copy of the settings stored in EEPROM
|
||||
|
||||
// *****************************************************************
|
||||
// public functions
|
||||
|
||||
int32_t saved_settings_save(void);
|
||||
|
||||
void saved_settings_init(void);
|
||||
|
||||
// *****************************************************************
|
||||
|
||||
#endif
|
@ -1,40 +0,0 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file stopwatch.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @brief Stop watch function
|
||||
* @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 __STOPWATCH_H__
|
||||
#define __STOPWATCH_H__
|
||||
|
||||
#include "stm32f10x.h"
|
||||
|
||||
// *****************************************************************************
|
||||
|
||||
void STOPWATCH_init(uint32_t resolution);
|
||||
void STOPWATCH_reset(void);
|
||||
uint32_t STOPWATCH_get_count(void);
|
||||
uint32_t STOPWATCH_get_us(void);
|
||||
|
||||
// *****************************************************************************
|
||||
|
||||
#endif
|
@ -1,40 +0,0 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file stream.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @brief Sends or Receives a continuous packet stream to/from the remote unit
|
||||
* @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 STREAM_H_
|
||||
#define STREAM_H_
|
||||
|
||||
#include "stdint.h"
|
||||
|
||||
// *************************************************************
|
||||
|
||||
void stream_1ms_tick(void);
|
||||
void stream_process(void);
|
||||
void stream_deinit(void);
|
||||
void stream_init(uint32_t our_sn);
|
||||
|
||||
// *************************************************************
|
||||
|
||||
#endif
|
@ -1,40 +0,0 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file transparent_comms.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @brief Serial communication port handling routines
|
||||
* @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 __TRANSPARENT_COMMS_H__
|
||||
#define __TRANSPARENT_COMMS_H__
|
||||
|
||||
#include "stdint.h"
|
||||
|
||||
// *****************************************************************************
|
||||
|
||||
void trans_1ms_tick(void);
|
||||
void trans_process(void);
|
||||
|
||||
void trans_init(void);
|
||||
|
||||
// *****************************************************************************
|
||||
|
||||
#endif
|
@ -1,939 +0,0 @@
|
||||
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file main.c
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @brief Main modem functions
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
*
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* This program is free software; you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation; either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful, but
|
||||
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
|
||||
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
|
||||
* for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License along
|
||||
* with this program; if not, write to the Free Software Foundation, Inc.,
|
||||
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
*/
|
||||
|
||||
|
||||
// *****************************************************************************
|
||||
|
||||
#define USE_WATCHDOG // comment this out if you don't want to use the watchdog
|
||||
|
||||
// *****************************************************************************
|
||||
// OpenPilot Includes
|
||||
|
||||
#include <string.h>
|
||||
|
||||
#include "crc.h"
|
||||
#include "aes.h"
|
||||
#include "rfm22b.h"
|
||||
#include "packet_handler.h"
|
||||
#include "stream.h"
|
||||
#include "ppm.h"
|
||||
#include "transparent_comms.h"
|
||||
//#include "api_comms.h"
|
||||
#include "api_config.h"
|
||||
#include "gpio_in.h"
|
||||
#include "stopwatch.h"
|
||||
#include "watchdog.h"
|
||||
#include "saved_settings.h"
|
||||
|
||||
#include "main.h"
|
||||
|
||||
/* Prototype of PIOS_Board_Init() function */
|
||||
extern void PIOS_Board_Init(void);
|
||||
|
||||
// *****************************************************************************
|
||||
// ADC data
|
||||
|
||||
#define ADC_REF 3.3f // ADC reference voltage
|
||||
#define ADC_FULL_RANGE 4096 // 12 bit ADC
|
||||
|
||||
#define ADC_PSU_RESISTOR_TOP 10000.0f // 10k upper resistor
|
||||
#define ADC_PSU_RESISTOR_BOTTOM 2700.0f // 2k7 lower resistor
|
||||
#define ADC_PSU_RATIO (ADC_PSU_RESISTOR_BOTTOM / (ADC_PSU_RESISTOR_TOP + ADC_PSU_RESISTOR_BOTTOM))
|
||||
#define ADC_PSU_mV_SCALE ((ADC_REF * 1000) / (ADC_FULL_RANGE * ADC_PSU_RATIO))
|
||||
|
||||
// *****************************************************************************
|
||||
// Global Variables
|
||||
|
||||
uint32_t flash_size;
|
||||
|
||||
char serial_number_str[25];
|
||||
uint32_t serial_number_crc32;
|
||||
|
||||
uint32_t reset_addr;
|
||||
|
||||
bool API_Mode;
|
||||
|
||||
bool booting;
|
||||
|
||||
volatile uint32_t random32;
|
||||
|
||||
// *****************************************************************************
|
||||
// Local Variables
|
||||
|
||||
#if defined(USE_WATCHDOG)
|
||||
volatile uint16_t watchdog_timer;
|
||||
uint16_t watchdog_delay;
|
||||
#endif
|
||||
|
||||
volatile bool inside_timer_int;
|
||||
volatile uint32_t uptime_ms;
|
||||
|
||||
volatile uint16_t second_tick_timer;
|
||||
volatile bool second_tick;
|
||||
|
||||
//volatile int32_t temp_adc;
|
||||
//volatile int32_t psu_adc;
|
||||
|
||||
// *****************************************************************************
|
||||
|
||||
#if defined(USE_WATCHDOG)
|
||||
|
||||
void processWatchdog(void)
|
||||
{
|
||||
// random32 = UpdateCRC32(random32, IWDG->SR);
|
||||
|
||||
if (watchdog_timer < watchdog_delay)
|
||||
return;
|
||||
|
||||
// the watchdog needs resetting
|
||||
|
||||
watchdog_timer = 0;
|
||||
|
||||
watchdog_Clear();
|
||||
}
|
||||
|
||||
void enableWatchdog(void)
|
||||
{ // enable a watchdog
|
||||
watchdog_timer = 0;
|
||||
watchdog_delay = watchdog_Init(1000); // 1 second watchdog timeout
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
// *****************************************************************************
|
||||
|
||||
void sequenceLEDs(void)
|
||||
{
|
||||
for (int i = 0; i < 2; i++)
|
||||
{
|
||||
USB_LED_ON;
|
||||
PIOS_DELAY_WaitmS(80);
|
||||
USB_LED_OFF;
|
||||
|
||||
LINK_LED_ON;
|
||||
PIOS_DELAY_WaitmS(80);
|
||||
LINK_LED_OFF;
|
||||
|
||||
RX_LED_ON;
|
||||
PIOS_DELAY_WaitmS(80);
|
||||
RX_LED_OFF;
|
||||
|
||||
TX_LED_ON;
|
||||
PIOS_DELAY_WaitmS(80);
|
||||
TX_LED_OFF;
|
||||
|
||||
#if defined(USE_WATCHDOG)
|
||||
processWatchdog(); // process the watchdog
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
||||
// *****************************************************************************
|
||||
// timer interrupt
|
||||
|
||||
void TIMER_INT_FUNC(void)
|
||||
{
|
||||
inside_timer_int = TRUE;
|
||||
|
||||
if (TIM_GetITStatus(TIMER_INT_TIMER, TIM_IT_Update) != RESET)
|
||||
{
|
||||
// Clear timer interrupt pending bit
|
||||
TIM_ClearITPendingBit(TIMER_INT_TIMER, TIM_IT_Update);
|
||||
|
||||
// random32 = UpdateCRC32(random32, PIOS_DELAY_GetuS() >> 8);
|
||||
// random32 = UpdateCRC32(random32, PIOS_DELAY_GetuS());
|
||||
|
||||
uptime_ms++;
|
||||
|
||||
#if defined(USE_WATCHDOG)
|
||||
watchdog_timer++;
|
||||
#endif
|
||||
|
||||
// ***********
|
||||
|
||||
if (!booting)
|
||||
{
|
||||
// ***********
|
||||
|
||||
if (++second_tick_timer >= 1000)
|
||||
{
|
||||
second_tick_timer -= 1000;
|
||||
second_tick = TRUE;
|
||||
}
|
||||
|
||||
// ***********
|
||||
|
||||
// read the chip temperature
|
||||
// temp_adc = PIOS_ADC_PinGet(0);
|
||||
|
||||
// read the psu voltage
|
||||
// psu_adc = PIOS_ADC_PinGet(1);
|
||||
|
||||
// ***********
|
||||
|
||||
uint8_t mode = saved_settings.mode;
|
||||
// modeTxBlankCarrierTest, // blank carrier Tx mode (for calibrating the carrier frequency say)
|
||||
// modeTxSpectrumTest // pseudo random Tx data mode (for checking the Tx carrier spectrum)
|
||||
|
||||
rfm22_1ms_tick(); // rf module tick
|
||||
|
||||
if (mode == MODE_NORMAL)
|
||||
ph_1ms_tick(); // packet handler tick
|
||||
|
||||
if (mode == MODE_STREAM_TX || mode == MODE_STREAM_RX)
|
||||
stream_1ms_tick(); // continuous data stream tick
|
||||
|
||||
if (mode == MODE_PPM_TX || mode == MODE_PPM_RX)
|
||||
ppm_1ms_tick(); // ppm tick
|
||||
|
||||
if (!API_Mode)
|
||||
trans_1ms_tick(); // transparent communications tick
|
||||
else
|
||||
// api_1ms_tick(); // api communications tick
|
||||
apiconfig_1ms_tick(); // api communications tick
|
||||
|
||||
// ***********
|
||||
}
|
||||
}
|
||||
|
||||
inside_timer_int = FALSE;
|
||||
}
|
||||
|
||||
void setup_TimerInt(uint16_t Hz)
|
||||
{ // setup the timer interrupt
|
||||
|
||||
// enable timer clock
|
||||
switch ((uint32_t)TIMER_INT_TIMER)
|
||||
{
|
||||
case (uint32_t)TIM1: RCC_APB2PeriphClockCmd(RCC_APB2Periph_TIM1, ENABLE); break;
|
||||
case (uint32_t)TIM2: RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM2, ENABLE); break;
|
||||
case (uint32_t)TIM3: RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM3, ENABLE); break;
|
||||
case (uint32_t)TIM4: RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM4, ENABLE); break;
|
||||
#ifdef STM32F10X_HD
|
||||
case (uint32_t)TIM5: RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM5, ENABLE); break;
|
||||
case (uint32_t)TIM6: RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM6, ENABLE); break;
|
||||
case (uint32_t)TIM7: RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM7, ENABLE); break;
|
||||
case (uint32_t)TIM8: RCC_APB2PeriphClockCmd(RCC_APB2Periph_TIM8, ENABLE); break;
|
||||
#endif
|
||||
}
|
||||
|
||||
// enable timer interrupt
|
||||
NVIC_InitTypeDef NVIC_InitStructure;
|
||||
switch ((uint32_t)TIMER_INT_TIMER)
|
||||
{
|
||||
// case (uint32_t)TIM1: NVIC_InitStructure.NVIC_IRQChannel = TIM1_IRQn; break;
|
||||
case (uint32_t)TIM2: NVIC_InitStructure.NVIC_IRQChannel = TIM2_IRQn; break;
|
||||
case (uint32_t)TIM3: NVIC_InitStructure.NVIC_IRQChannel = TIM3_IRQn; break;
|
||||
case (uint32_t)TIM4: NVIC_InitStructure.NVIC_IRQChannel = TIM4_IRQn; break;
|
||||
#ifdef STM32F10X_HD
|
||||
case (uint32_t)TIM5: NVIC_InitStructure.NVIC_IRQChannel = TIM5_IRQn; break;
|
||||
case (uint32_t)TIM6: NVIC_InitStructure.NVIC_IRQChannel = TIM6_IRQn; break;
|
||||
case (uint32_t)TIM7: NVIC_InitStructure.NVIC_IRQChannel = TIM7_IRQn; break;
|
||||
// case (uint32_t)TIM8: NVIC_InitStructure.NVIC_IRQChannel = TIM8_IRQn; break;
|
||||
#endif
|
||||
}
|
||||
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = TIMER_INT_PRIORITY;
|
||||
NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0;
|
||||
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
|
||||
NVIC_Init(&NVIC_InitStructure);
|
||||
|
||||
// Time base configuration
|
||||
TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure;
|
||||
TIM_TimeBaseStructInit(&TIM_TimeBaseStructure);
|
||||
TIM_TimeBaseStructure.TIM_Period = (1000000 / Hz) - 1;
|
||||
TIM_TimeBaseStructure.TIM_Prescaler = (PIOS_MASTER_CLOCK / 1000000) - 1; // For 1 uS accuracy
|
||||
TIM_TimeBaseStructure.TIM_ClockDivision = TIM_CKD_DIV1;
|
||||
TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up;
|
||||
TIM_TimeBaseInit(TIMER_INT_TIMER, &TIM_TimeBaseStructure);
|
||||
|
||||
// Enable the CC2 Interrupt Request
|
||||
TIM_ITConfig(TIMER_INT_TIMER, TIM_IT_Update, ENABLE);
|
||||
|
||||
// Clear update pending flag
|
||||
TIM_ClearFlag(TIMER_INT_TIMER, TIM_FLAG_Update);
|
||||
|
||||
// Enable counter
|
||||
TIM_Cmd(TIMER_INT_TIMER, ENABLE);
|
||||
}
|
||||
|
||||
// *****************************************************************************
|
||||
// read the CPU's flash and ram sizes
|
||||
|
||||
void get_CPUDetails(void)
|
||||
{
|
||||
// read the flash size
|
||||
flash_size = (uint32_t)mem16(0x1FFFF7E0) * 1024;
|
||||
|
||||
int j = 0;
|
||||
|
||||
// read the CPU electronic signature (12-bytes)
|
||||
serial_number_str[j] = 0;
|
||||
for (int i = 0; i < 12; i++)
|
||||
{
|
||||
uint8_t ms_nibble = mem8(0x1ffff7e8 + i) >> 4;
|
||||
uint8_t ls_nibble = mem8(0x1ffff7e8 + i) & 0x0f;
|
||||
if (j > sizeof(serial_number_str) - 3) break;
|
||||
serial_number_str[j++] = ((ms_nibble > 9) ? ('A' - 10) : '0') + ms_nibble;
|
||||
serial_number_str[j++] = ((ls_nibble > 9) ? ('A' - 10) : '0') + ls_nibble;
|
||||
serial_number_str[j] = 0;
|
||||
}
|
||||
|
||||
// create a 32-bit crc from the serial number hex string
|
||||
serial_number_crc32 = updateCRC32Data(0xffffffff, serial_number_str, j);
|
||||
serial_number_crc32 = updateCRC32(serial_number_crc32, j);
|
||||
|
||||
// reset_addr = (uint32_t)&Reset_Handler;
|
||||
}
|
||||
|
||||
// *****************************************************************************
|
||||
|
||||
void init_RF_module(void)
|
||||
{
|
||||
int i = -100;
|
||||
|
||||
switch (saved_settings.frequency_band)
|
||||
{
|
||||
case FREQBAND_434MHz:
|
||||
case FREQBAND_868MHz:
|
||||
case FREQBAND_915MHz:
|
||||
i = rfm22_init_normal(saved_settings.min_frequency_Hz, saved_settings.max_frequency_Hz, 50000);
|
||||
break;
|
||||
|
||||
default:
|
||||
#if defined(PIOS_COM_DEBUG)
|
||||
DEBUG_PRINTF("UNKNOWN BAND ERROR\r\n\r\n", i);
|
||||
#endif
|
||||
|
||||
for (int j = 0; j < 16; j++)
|
||||
{
|
||||
USB_LED_ON;
|
||||
LINK_LED_OFF;
|
||||
RX_LED_ON;
|
||||
TX_LED_OFF;
|
||||
|
||||
PIOS_DELAY_WaitmS(200);
|
||||
|
||||
USB_LED_OFF;
|
||||
LINK_LED_ON;
|
||||
RX_LED_OFF;
|
||||
TX_LED_ON;
|
||||
|
||||
PIOS_DELAY_WaitmS(200);
|
||||
|
||||
#if defined(USE_WATCHDOG)
|
||||
processWatchdog();
|
||||
#endif
|
||||
}
|
||||
|
||||
PIOS_DELAY_WaitmS(1000);
|
||||
|
||||
PIOS_SYS_Reset();
|
||||
|
||||
while (1);
|
||||
break;
|
||||
}
|
||||
|
||||
if (i < 0)
|
||||
{ // RF module error .. flash the LED's
|
||||
|
||||
#if defined(PIOS_COM_DEBUG)
|
||||
DEBUG_PRINTF("RF ERROR res: %d\r\n\r\n", i);
|
||||
#endif
|
||||
|
||||
for (int j = 0; j < 16; j++)
|
||||
{
|
||||
USB_LED_ON;
|
||||
LINK_LED_ON;
|
||||
RX_LED_OFF;
|
||||
TX_LED_OFF;
|
||||
|
||||
PIOS_DELAY_WaitmS(200);
|
||||
|
||||
USB_LED_OFF;
|
||||
LINK_LED_OFF;
|
||||
RX_LED_ON;
|
||||
TX_LED_ON;
|
||||
|
||||
PIOS_DELAY_WaitmS(200);
|
||||
|
||||
#if defined(USE_WATCHDOG)
|
||||
processWatchdog();
|
||||
#endif
|
||||
}
|
||||
|
||||
PIOS_DELAY_WaitmS(1000);
|
||||
|
||||
PIOS_SYS_Reset();
|
||||
|
||||
while (1);
|
||||
}
|
||||
|
||||
rfm22_setFreqCalibration(saved_settings.rf_xtal_cap);
|
||||
rfm22_setNominalCarrierFrequency(saved_settings.frequency_Hz);
|
||||
rfm22_setDatarate(saved_settings.max_rf_bandwidth, TRUE);
|
||||
rfm22_setTxPower(saved_settings.max_tx_power);
|
||||
}
|
||||
|
||||
// *****************************************************************************
|
||||
// find out what caused our reset and act on it
|
||||
|
||||
void processReset(void)
|
||||
{
|
||||
if (RCC_GetFlagStatus(RCC_FLAG_IWDGRST) != RESET)
|
||||
{ // Independant Watchdog Reset
|
||||
|
||||
#if defined(PIOS_COM_DEBUG)
|
||||
DEBUG_PRINTF("\r\nINDEPENDANT WATCHDOG CAUSED A RESET\r\n");
|
||||
#endif
|
||||
|
||||
// all led's ON
|
||||
USB_LED_ON;
|
||||
LINK_LED_ON;
|
||||
RX_LED_ON;
|
||||
TX_LED_ON;
|
||||
|
||||
PIOS_DELAY_WaitmS(500); // delay a bit
|
||||
|
||||
// all led's OFF
|
||||
USB_LED_OFF;
|
||||
LINK_LED_OFF;
|
||||
RX_LED_OFF;
|
||||
TX_LED_OFF;
|
||||
|
||||
}
|
||||
/*
|
||||
if (RCC_GetFlagStatus(RCC_FLAG_WWDGRST) != RESET)
|
||||
{ // Window Watchdog Reset
|
||||
|
||||
DEBUG_PRINTF("\r\nWINDOW WATCHDOG CAUSED A REBOOT\r\n");
|
||||
|
||||
// all led's ON
|
||||
USB_LED_ON;
|
||||
LINK_LED_ON;
|
||||
RX_LED_ON;
|
||||
TX_LED_ON;
|
||||
|
||||
PIOS_DELAY_WaitmS(500); // delay a bit
|
||||
|
||||
// all led's OFF
|
||||
USB_LED_OFF;
|
||||
LINK_LED_OFF;
|
||||
RX_LED_OFF;
|
||||
TX_LED_OFF;
|
||||
}
|
||||
*/
|
||||
if (RCC_GetFlagStatus(RCC_FLAG_PORRST) != RESET)
|
||||
{ // Power-On Reset
|
||||
#if defined(PIOS_COM_DEBUG)
|
||||
DEBUG_PRINTF("\r\nPOWER-ON-RESET\r\n");
|
||||
#endif
|
||||
}
|
||||
|
||||
if (RCC_GetFlagStatus(RCC_FLAG_SFTRST) != RESET)
|
||||
{ // Software Reset
|
||||
#if defined(PIOS_COM_DEBUG)
|
||||
DEBUG_PRINTF("\r\nSOFTWARE RESET\r\n");
|
||||
#endif
|
||||
}
|
||||
|
||||
if (RCC_GetFlagStatus(RCC_FLAG_LPWRRST) != RESET)
|
||||
{ // Low-Power Reset
|
||||
#if defined(PIOS_COM_DEBUG)
|
||||
DEBUG_PRINTF("\r\nLOW POWER RESET\r\n");
|
||||
#endif
|
||||
}
|
||||
|
||||
if (RCC_GetFlagStatus(RCC_FLAG_PINRST) != RESET)
|
||||
{ // Pin Reset
|
||||
#if defined(PIOS_COM_DEBUG)
|
||||
DEBUG_PRINTF("\r\nPIN RESET\r\n");
|
||||
#endif
|
||||
}
|
||||
|
||||
// Clear reset flags
|
||||
RCC_ClearFlag();
|
||||
}
|
||||
|
||||
// *****************************************************************************
|
||||
// Main function
|
||||
|
||||
int main()
|
||||
{
|
||||
// *************
|
||||
// init various variables
|
||||
|
||||
booting = TRUE;
|
||||
|
||||
inside_timer_int = FALSE;
|
||||
|
||||
uptime_ms = 0;
|
||||
|
||||
flash_size = 0;
|
||||
|
||||
serial_number_str[0] = 0;
|
||||
serial_number_crc32 = 0;
|
||||
|
||||
reset_addr = 0;
|
||||
|
||||
// temp_adc = -1;
|
||||
// psu_adc = -1;
|
||||
|
||||
// API_Mode = FALSE;
|
||||
API_Mode = TRUE; // TEST ONLY
|
||||
|
||||
second_tick_timer = 0;
|
||||
second_tick = FALSE;
|
||||
|
||||
saved_settings.frequency_band = FREQBAND_UNKNOWN;
|
||||
|
||||
// *************
|
||||
|
||||
PIOS_Board_Init();
|
||||
|
||||
CRC_init();
|
||||
|
||||
// read the CPU details
|
||||
get_CPUDetails();
|
||||
|
||||
// setup the GPIO input pins
|
||||
GPIO_IN_Init();
|
||||
|
||||
// *************
|
||||
// set various GPIO pin states
|
||||
|
||||
// uart serial RTS line high
|
||||
SERIAL_RTS_ENABLE;
|
||||
SERIAL_RTS_SET;
|
||||
|
||||
// RF module chip-select line high
|
||||
RF_CS_ENABLE;
|
||||
RF_CS_HIGH;
|
||||
|
||||
// PPM OUT low
|
||||
PPM_OUT_ENABLE;
|
||||
PPM_OUT_LOW;
|
||||
|
||||
// pin high
|
||||
SPARE1_ENABLE;
|
||||
SPARE1_HIGH;
|
||||
|
||||
// pin high
|
||||
SPARE2_ENABLE;
|
||||
SPARE2_HIGH;
|
||||
|
||||
// pin high
|
||||
SPARE3_ENABLE;
|
||||
SPARE3_HIGH;
|
||||
|
||||
// pin high
|
||||
SPARE4_ENABLE;
|
||||
SPARE4_HIGH;
|
||||
|
||||
// pin high
|
||||
SPARE5_ENABLE;
|
||||
SPARE5_HIGH;
|
||||
|
||||
// *************
|
||||
|
||||
random32 ^= serial_number_crc32; // try to randomise the random number
|
||||
// random32 ^= serial_number_crc32 ^ CRC_IDR; // try to randomise the random number
|
||||
|
||||
trans_init(); // initialise the transparent communications module
|
||||
|
||||
// api_init(); // initialise the API communications module
|
||||
apiconfig_init(); // initialise the API communications module
|
||||
|
||||
setup_TimerInt(1000); // setup a 1kHz timer interrupt
|
||||
|
||||
#if defined(USE_WATCHDOG)
|
||||
enableWatchdog(); // enable the watchdog
|
||||
#endif
|
||||
|
||||
// *************
|
||||
// do a simple LED flash test sequence so the user knows all the led's are working and that we have booted
|
||||
|
||||
PIOS_DELAY_WaitmS(100);
|
||||
|
||||
// turn all the leds off
|
||||
USB_LED_OFF;
|
||||
LINK_LED_OFF;
|
||||
RX_LED_OFF;
|
||||
TX_LED_OFF;
|
||||
|
||||
PIOS_DELAY_WaitmS(200);
|
||||
|
||||
sequenceLEDs();
|
||||
|
||||
// turn all the leds off
|
||||
USB_LED_OFF;
|
||||
LINK_LED_OFF;
|
||||
RX_LED_OFF;
|
||||
TX_LED_OFF;
|
||||
|
||||
// *************
|
||||
|
||||
#if defined(PIOS_COM_DEBUG)
|
||||
DEBUG_PRINTF("\r\n");
|
||||
DEBUG_PRINTF("PipXtreme v%u.%u rebooted\r\n", VERSION_MAJOR, VERSION_MINOR);
|
||||
DEBUG_PRINTF("\r\n");
|
||||
DEBUG_PRINTF("CPU flash size: %u\r\n", flash_size);
|
||||
DEBUG_PRINTF("CPU serial number: %s %08X\r\n", serial_number_str, serial_number_crc32);
|
||||
// DEBUG_PRINTF("Reset address: %08X\r\n", reset_addr);
|
||||
#endif
|
||||
|
||||
// *************
|
||||
// initialise the saved settings module
|
||||
|
||||
saved_settings_init();
|
||||
|
||||
if (saved_settings.mode == 0xff ||
|
||||
saved_settings.mode == MODE_TX_BLANK_CARRIER_TEST ||
|
||||
saved_settings.mode == MODE_TX_SPECTRUM_TEST ||
|
||||
saved_settings.mode == MODE_SCAN_SPECTRUM)
|
||||
saved_settings.mode = MODE_NORMAL; // go back to NORMAL mode
|
||||
|
||||
if (saved_settings.rts_time == 0xff || saved_settings.rts_time > 100)
|
||||
saved_settings.rts_time = 10; // default to 10ms
|
||||
|
||||
#if !defined(PIOS_COM_DEBUG)
|
||||
if (saved_settings.serial_baudrate != 0xffffffff)
|
||||
PIOS_COM_ChangeBaud(PIOS_COM_SERIAL, saved_settings.serial_baudrate);
|
||||
#endif
|
||||
|
||||
// *************
|
||||
// read the API mode pin
|
||||
|
||||
if (!GPIO_IN(API_MODE_PIN))
|
||||
API_Mode = TRUE;
|
||||
|
||||
#if defined(PIOS_COM_DEBUG)
|
||||
if (!API_Mode)
|
||||
DEBUG_PRINTF("TRANSPARENT mode\r\n");
|
||||
else
|
||||
DEBUG_PRINTF("API mode\r\n");
|
||||
#endif
|
||||
|
||||
// *************
|
||||
// read the 434/868/915 jumper options
|
||||
|
||||
if (!GPIO_IN(_868MHz_PIN) && !GPIO_IN(_915MHz_PIN)) saved_settings.frequency_band = FREQBAND_434MHz; // 434MHz band
|
||||
else
|
||||
if (!GPIO_IN(_868MHz_PIN) && GPIO_IN(_915MHz_PIN)) saved_settings.frequency_band = FREQBAND_868MHz; // 868MHz band
|
||||
else
|
||||
if ( GPIO_IN(_868MHz_PIN) && !GPIO_IN(_915MHz_PIN)) saved_settings.frequency_band = FREQBAND_915MHz; // 915MHz band
|
||||
|
||||
// set some defaults if they are not set
|
||||
switch (saved_settings.frequency_band)
|
||||
{
|
||||
case FREQBAND_434MHz:
|
||||
|
||||
if (saved_settings.min_frequency_Hz == 0xffffffff)
|
||||
{
|
||||
saved_settings.frequency_Hz = 434000000;
|
||||
saved_settings.min_frequency_Hz = saved_settings.frequency_Hz - 2000000;
|
||||
saved_settings.max_frequency_Hz = saved_settings.frequency_Hz + 2000000;
|
||||
}
|
||||
if (saved_settings.max_rf_bandwidth == 0xffffffff)
|
||||
{
|
||||
// saved_settings.max_rf_bandwidth = 500;
|
||||
// saved_settings.max_rf_bandwidth = 1000;
|
||||
// saved_settings.max_rf_bandwidth = 2000;
|
||||
// saved_settings.max_rf_bandwidth = 4000;
|
||||
// saved_settings.max_rf_bandwidth = 8000;
|
||||
// saved_settings.max_rf_bandwidth = 9600;
|
||||
// saved_settings.max_rf_bandwidth = 16000;
|
||||
// saved_settings.max_rf_bandwidth = 19200;
|
||||
// saved_settings.max_rf_bandwidth = 24000;
|
||||
// saved_settings.max_rf_bandwidth = 32000;
|
||||
// saved_settings.max_rf_bandwidth = 64000;
|
||||
saved_settings.max_rf_bandwidth = 128000;
|
||||
// saved_settings.max_rf_bandwidth = 192000;
|
||||
}
|
||||
if (saved_settings.max_tx_power == 0xff)
|
||||
{
|
||||
saved_settings.max_tx_power = RFM22_tx_pwr_txpow_0; // +1dBm ... 1.25mW
|
||||
// saved_settings.max_tx_power = RFM22_tx_pwr_txpow_1; // +2dBm ... 1.6mW
|
||||
// saved_settings.max_tx_power = RFM22_tx_pwr_txpow_2; // +5dBm ... 3.16mW
|
||||
// saved_settings.max_tx_power = RFM22_tx_pwr_txpow_3; // +8dBm ... 6.3mW
|
||||
// saved_settings.max_tx_power = RFM22_tx_pwr_txpow_4; // +11dBm .. 12.6mW
|
||||
// saved_settings.max_tx_power = RFM22_tx_pwr_txpow_5; // +14dBm .. 25mW
|
||||
// saved_settings.max_tx_power = RFM22_tx_pwr_txpow_6; // +17dBm .. 50mW
|
||||
// saved_settings.max_tx_power = RFM22_tx_pwr_txpow_7; // +20dBm .. 100mW
|
||||
}
|
||||
break;
|
||||
|
||||
case FREQBAND_868MHz:
|
||||
if (saved_settings.min_frequency_Hz == 0xffffffff)
|
||||
{
|
||||
saved_settings.frequency_Hz = 868000000;
|
||||
saved_settings.min_frequency_Hz = saved_settings.frequency_Hz - 10000000;
|
||||
saved_settings.max_frequency_Hz = saved_settings.frequency_Hz + 10000000;
|
||||
}
|
||||
if (saved_settings.max_rf_bandwidth == 0xffffffff)
|
||||
saved_settings.max_rf_bandwidth = 128000;
|
||||
if (saved_settings.max_tx_power == 0xff)
|
||||
saved_settings.max_tx_power = RFM22_tx_pwr_txpow_0; // +1dBm ... 1.25mW
|
||||
break;
|
||||
|
||||
case FREQBAND_915MHz:
|
||||
if (saved_settings.min_frequency_Hz == 0xffffffff)
|
||||
{
|
||||
saved_settings.frequency_Hz = 915000000;
|
||||
saved_settings.min_frequency_Hz = saved_settings.frequency_Hz - 13000000;
|
||||
saved_settings.max_frequency_Hz = saved_settings.frequency_Hz + 13000000;
|
||||
}
|
||||
if (saved_settings.max_rf_bandwidth == 0xffffffff)
|
||||
saved_settings.max_rf_bandwidth = 128000;
|
||||
if (saved_settings.max_tx_power == 0xff)
|
||||
saved_settings.max_tx_power = RFM22_tx_pwr_txpow_0; // +1dBm ... 1.25mW
|
||||
break;
|
||||
|
||||
default:
|
||||
break;
|
||||
}
|
||||
|
||||
#if defined(PIOS_COM_DEBUG)
|
||||
switch (saved_settings.frequency_band)
|
||||
{
|
||||
case FREQBAND_UNKNOWN: DEBUG_PRINTF("UNKNOWN band\r\n"); break;
|
||||
case FREQBAND_434MHz: DEBUG_PRINTF("434MHz band\r\n"); break;
|
||||
case FREQBAND_868MHz: DEBUG_PRINTF("868MHz band\r\n"); break;
|
||||
case FREQBAND_915MHz: DEBUG_PRINTF("915MHz band\r\n"); break;
|
||||
}
|
||||
#endif
|
||||
|
||||
// *************
|
||||
|
||||
processReset(); // Determine what caused the reset/reboot
|
||||
|
||||
init_RF_module(); // initialise the RF module
|
||||
|
||||
// *************
|
||||
|
||||
#if defined(PIOS_COM_DEBUG)
|
||||
DEBUG_PRINTF("\r\n");
|
||||
DEBUG_PRINTF("RF datarate: %dbps\r\n", ph_getDatarate());
|
||||
DEBUG_PRINTF("RF frequency: %dHz\r\n", rfm22_getNominalCarrierFrequency());
|
||||
DEBUG_PRINTF("RF TX power: %d\r\n", ph_getTxPower());
|
||||
|
||||
DEBUG_PRINTF("\r\nUnit mode: ");
|
||||
switch (saved_settings.mode)
|
||||
{
|
||||
case MODE_NORMAL: DEBUG_PRINTF("NORMAL\r\n"); break;
|
||||
case MODE_STREAM_TX: DEBUG_PRINTF("STREAM-TX\r\n"); break;
|
||||
case MODE_STREAM_RX: DEBUG_PRINTF("STREAM-RX\r\n"); break;
|
||||
case MODE_PPM_TX: DEBUG_PRINTF("PPM-TX\r\n"); break;
|
||||
case MODE_PPM_RX: DEBUG_PRINTF("PPM-RX\r\n"); break;
|
||||
case MODE_SCAN_SPECTRUM: DEBUG_PRINTF("SCAN-SPECTRUM\r\n"); break;
|
||||
case MODE_TX_BLANK_CARRIER_TEST: DEBUG_PRINTF("TX-BLANK-CARRIER\r\n"); break;
|
||||
case MODE_TX_SPECTRUM_TEST: DEBUG_PRINTF("TX_SPECTRUM\r\n"); break;
|
||||
default: DEBUG_PRINTF("UNKNOWN [%u]\r\n", saved_settings.mode); break;
|
||||
}
|
||||
#endif
|
||||
|
||||
switch (saved_settings.mode)
|
||||
{
|
||||
case MODE_NORMAL:
|
||||
ph_init(serial_number_crc32); // initialise the packet handler
|
||||
break;
|
||||
|
||||
case MODE_STREAM_TX:
|
||||
case MODE_STREAM_RX:
|
||||
stream_init(serial_number_crc32); // initialise the continuous packet stream module
|
||||
break;
|
||||
|
||||
case MODE_PPM_TX:
|
||||
case MODE_PPM_RX:
|
||||
ppm_init(serial_number_crc32); // initialise the ppm module
|
||||
break;
|
||||
|
||||
case MODE_SCAN_SPECTRUM:
|
||||
case MODE_TX_BLANK_CARRIER_TEST:
|
||||
case MODE_TX_SPECTRUM_TEST:
|
||||
break;
|
||||
}
|
||||
|
||||
// *************
|
||||
// Main executive loop
|
||||
|
||||
saved_settings_save();
|
||||
|
||||
booting = FALSE;
|
||||
|
||||
for (;;)
|
||||
{
|
||||
random32 = updateCRC32(random32, PIOS_DELAY_GetuS() >> 8);
|
||||
random32 = updateCRC32(random32, PIOS_DELAY_GetuS());
|
||||
|
||||
if (second_tick)
|
||||
{
|
||||
second_tick = FALSE;
|
||||
|
||||
// *************************
|
||||
// display the up-time .. HH:MM:SS
|
||||
|
||||
// #if defined(PIOS_COM_DEBUG)
|
||||
// uint32_t _uptime_ms = uptime_ms;
|
||||
// uint32_t _uptime_sec = _uptime_ms / 1000;
|
||||
// DEBUG_PRINTF("Uptime: %02d:%02d:%02d.%03d\r\n", _uptime_sec / 3600, (_uptime_sec / 60) % 60, _uptime_sec % 60, _uptime_ms % 1000);
|
||||
// #endif
|
||||
|
||||
// *************************
|
||||
// process the Temperature
|
||||
|
||||
// if (temp_adc >= 0)
|
||||
// {
|
||||
// int32_t degress_C = temp_adc;
|
||||
//
|
||||
// #if defined(PIOS_COM_DEBUG)
|
||||
// DEBUG_PRINTF("TEMP: %d %d\r\n", temp_adc, degress_C);
|
||||
// #endif
|
||||
// }
|
||||
|
||||
// *************************
|
||||
// process the PSU voltage level
|
||||
|
||||
// if (psu_adc >= 0)
|
||||
// {
|
||||
// int32_t psu_mV = psu_adc * ADC_PSU_mV_SCALE;
|
||||
//
|
||||
// #if defined(PIOS_COM_DEBUG)
|
||||
// DEBUG_PRINTF("PSU: %d, %dmV\r\n", psu_adc, psu_mV);
|
||||
// #endif
|
||||
// }
|
||||
|
||||
// *************************
|
||||
}
|
||||
|
||||
rfm22_process(); // rf hardware layer processing
|
||||
|
||||
uint8_t mode = saved_settings.mode;
|
||||
// modeTxBlankCarrierTest, // blank carrier Tx mode (for calibrating the carrier frequency say)
|
||||
// modeTxSpectrumTest // pseudo random Tx data mode (for checking the Tx carrier spectrum)
|
||||
|
||||
if (mode == MODE_NORMAL)
|
||||
ph_process(); // packet handler processing
|
||||
|
||||
if (mode == MODE_STREAM_TX || mode == MODE_STREAM_RX)
|
||||
stream_process(); // continuous data stream processing
|
||||
|
||||
if (mode == MODE_PPM_TX || mode == MODE_PPM_RX)
|
||||
ppm_process(); // ppm processing
|
||||
|
||||
if (!API_Mode)
|
||||
trans_process(); // tranparent local communication processing (serial port and usb port)
|
||||
else
|
||||
// api_process(); // API local communication processing (serial port and usb port)
|
||||
apiconfig_process(); // API local communication processing (serial port and usb port)
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
// ******************
|
||||
// TEST ONLY ... get/put data over the radio link .. speed testing .. comment out trans_process() and api_process() if testing with this
|
||||
/*
|
||||
int connection_index = 0;
|
||||
|
||||
if (ph_connected(connection_index))
|
||||
{ // we have a connection to a remote modem
|
||||
|
||||
uint8_t buffer[128];
|
||||
|
||||
uint16_t num = ph_getData_used(connection_index); // number of bytes waiting for us to get
|
||||
if (num > 0)
|
||||
{ // their is data in the received buffer - fetch it
|
||||
if (num > sizeof(buffer)) num = sizeof(buffer);
|
||||
num = ph_getData(connection_index, buffer, num); // fetch the received data
|
||||
}
|
||||
|
||||
// keep the tx buffer topped up
|
||||
num = ph_putData_free(connection_index);
|
||||
if (num > 0)
|
||||
{ // their is space available in the transmit buffer - top it up
|
||||
if (num > sizeof(buffer)) num = sizeof(buffer);
|
||||
for (int16_t i = 0; i < num; i++) buffer[i] = i;
|
||||
num = ph_putData(connection_index, buffer, num);
|
||||
}
|
||||
}
|
||||
*/
|
||||
// ******************
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
#if defined(USE_WATCHDOG)
|
||||
processWatchdog(); // process the watchdog
|
||||
#endif
|
||||
}
|
||||
|
||||
// *************
|
||||
// we should never arrive here
|
||||
|
||||
// disable all interrupts
|
||||
PIOS_IRQ_Disable();
|
||||
|
||||
// turn off all leds
|
||||
USB_LED_OFF;
|
||||
LINK_LED_OFF;
|
||||
RX_LED_OFF;
|
||||
TX_LED_OFF;
|
||||
|
||||
PIOS_SYS_Reset();
|
||||
|
||||
while (1);
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
// *****************************************************************************
|
@ -1,1724 +0,0 @@
|
||||
/******************************************************************************
|
||||
*
|
||||
* @file packet_handler.c
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @brief Modem packet handling routines
|
||||
* @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
|
||||
*/
|
||||
|
||||
|
||||
// ********
|
||||
|
||||
// We use 128-bit AES CBC encryption if encryption is enabled
|
||||
|
||||
|
||||
// encrypted packet format
|
||||
// 16-byte CBC .. 1st byte must not be zero
|
||||
// 4-byte source id
|
||||
// 4-byte destination id
|
||||
// 1-byte packet type
|
||||
// 1-byte tx sequence value
|
||||
// 1-byte rx sequence value
|
||||
// 1-byte data size
|
||||
// 4-byte crc of entire packet not including CBC bytes
|
||||
|
||||
|
||||
// unencrypted packet format
|
||||
// 1-byte null byte .. set to zero to indicate packet is not encrypted
|
||||
// 4-byte source id
|
||||
// 4-byte destination id
|
||||
// 1-byte packet type
|
||||
// 1-byte tx sequence value
|
||||
// 1-byte rx sequence value
|
||||
// 1-byte data size
|
||||
// 4-byte crc of entire packet not including the null byte
|
||||
|
||||
// ********
|
||||
|
||||
#include <string.h> // memmove
|
||||
|
||||
#include "main.h"
|
||||
#include "rfm22b.h"
|
||||
#include "fifo_buffer.h"
|
||||
#include "aes.h"
|
||||
#include "crc.h"
|
||||
#include "saved_settings.h"
|
||||
#include "packet_handler.h"
|
||||
|
||||
#if defined(PIOS_COM_DEBUG)
|
||||
// #define PACKET_DEBUG
|
||||
#endif
|
||||
|
||||
// *****************************************************************************
|
||||
|
||||
#define PH_FIFO_BUFFER_SIZE 2048 // FIFO buffer size
|
||||
|
||||
// *****************************************************************************
|
||||
|
||||
#define AES_BLOCK_SIZE 16 // AES encryption does it in 16-byte blocks ONLY
|
||||
|
||||
// default aes 128-bit encryption key
|
||||
const uint8_t default_aes_key[AES_BLOCK_SIZE] = {0x65, 0x3b, 0x71, 0x89, 0x4a, 0xf4, 0xc8, 0xcb, 0x18, 0xd4, 0x9b, 0x4d, 0x4a, 0xbe, 0xc8, 0x37};
|
||||
|
||||
// *****************************************************************************
|
||||
|
||||
#define RETRY_RECONNECT_COUNT 60 // if transmission retries this many times then reset the link to the remote modem
|
||||
|
||||
#define PACKET_TYPE_DATA_COMP_BIT 0x80 // data compressed bit. if set then the data in the packet is compressed
|
||||
#define PACKET_TYPE_MASK 0x7f // packet type mask
|
||||
|
||||
enum {
|
||||
PACKET_TYPE_NONE = 0,
|
||||
|
||||
PACKET_TYPE_CONNECT, // for requesting a connection
|
||||
PACKET_TYPE_CONNECT_ACK, // ack
|
||||
|
||||
PACKET_TYPE_DISCONNECT, // to tell the other modem they cannot connect to us
|
||||
|
||||
PACKET_TYPE_DATA, // data packet (packet contains user data)
|
||||
PACKET_TYPE_DATA_ACK, // ack
|
||||
|
||||
PACKET_TYPE_READY, // tells the other modem we are ready to accept more data
|
||||
PACKET_TYPE_READY_ACK, // ack
|
||||
|
||||
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_NOTREADY_ACK, // ack
|
||||
|
||||
PACKET_TYPE_DATARATE, // for changing the RF data rate
|
||||
PACKET_TYPE_DATARATE_ACK, // ack
|
||||
|
||||
PACKET_TYPE_PING, // used to check link is still up
|
||||
PACKET_TYPE_PONG, // ack
|
||||
|
||||
PACKET_TYPE_ADJUST_TX_PWR, // used to ask the other modem to adjust it's tx power
|
||||
PACKET_TYPE_ADJUST_TX_PWR_ACK // ack
|
||||
};
|
||||
|
||||
#define BROADCAST_ADDR 0xffffffff
|
||||
|
||||
//#pragma pack(push)
|
||||
//#pragma pack(1)
|
||||
|
||||
typedef struct
|
||||
{
|
||||
uint32_t source_id;
|
||||
uint32_t destination_id;
|
||||
uint8_t type;
|
||||
uint8_t tx_seq;
|
||||
uint8_t rx_seq;
|
||||
uint8_t data_size;
|
||||
uint32_t crc;
|
||||
} __attribute__((__packed__)) t_packet_header;
|
||||
|
||||
// this structure must be a multiple of 'AES_BLOCK_SIZE' bytes in size and no more than 255 bytes in size
|
||||
typedef struct
|
||||
{
|
||||
uint8_t cbc[AES_BLOCK_SIZE]; // AES encryption Cipher-Block-Chaining key .. 1st byte must not be zero - to indicate the packet is encrypted
|
||||
t_packet_header header;
|
||||
uint8_t data[240 - sizeof(t_packet_header) - AES_BLOCK_SIZE];
|
||||
} __attribute__((__packed__)) t_encrypted_packet;
|
||||
|
||||
// this structure must be no more than 255 bytes in size (255 = the maximum packet size)
|
||||
typedef struct
|
||||
{
|
||||
uint8_t null_byte; // this must be set to zero - to indicate the packet is unencrypted
|
||||
t_packet_header header;
|
||||
uint8_t data[255 - sizeof(t_packet_header) - 1];
|
||||
} __attribute__((__packed__)) t_unencrypted_packet;
|
||||
|
||||
//#pragma pack(pop)
|
||||
|
||||
// *****************************************************************************
|
||||
// link state for each remote connection
|
||||
|
||||
enum {
|
||||
LINK_DISCONNECTED = 0,
|
||||
LINK_CONNECTING,
|
||||
LINK_CONNECTED
|
||||
};
|
||||
|
||||
typedef struct
|
||||
{
|
||||
uint32_t serial_number; // their serial number
|
||||
|
||||
uint8_t tx_buffer[PH_FIFO_BUFFER_SIZE] __attribute__ ((aligned(4)));
|
||||
t_fifo_buffer tx_fifo_buffer; // holds the data to be transmitted to the other modem
|
||||
|
||||
uint8_t rx_buffer[PH_FIFO_BUFFER_SIZE] __attribute__ ((aligned(4)));
|
||||
t_fifo_buffer rx_fifo_buffer; // holds the data received from the other modem
|
||||
|
||||
uint8_t link_state; // holds our current RF link state
|
||||
|
||||
uint8_t tx_sequence; // incremented with each data packet transmitted, sent in every packet transmitted
|
||||
uint8_t tx_sequence_data_size; // the size of data we sent in our last packet
|
||||
|
||||
uint8_t rx_sequence; // incremented with each data packet received contain data, sent in every packet transmitted
|
||||
|
||||
volatile uint16_t tx_packet_timer; // ms .. used for packet timing
|
||||
|
||||
uint16_t tx_retry_time_slots; // add's some random packet transmission timing - to try to prevent transmission collisions
|
||||
uint16_t tx_retry_time_slot_len; // ms .. " " "
|
||||
uint16_t tx_retry_time; // ms .. " " "
|
||||
uint16_t tx_retry_counter; // incremented on each transmission, reset back to '0' when we receive an ack to our transmission
|
||||
|
||||
volatile uint16_t data_speed_timer; // used for calculating the transmit/receive data rate
|
||||
volatile uint32_t tx_data_speed_count; // incremented with the number of data bits we send in our transmit packets
|
||||
volatile uint32_t tx_data_speed; // holds the number of data bits we have sent each second
|
||||
volatile uint32_t rx_data_speed_count; // incremented with the number of data bits we send in our transmit packets
|
||||
volatile uint32_t rx_data_speed; // holds the number of data bits we have received each second
|
||||
|
||||
uint16_t ping_time; // ping timer
|
||||
uint16_t fast_ping_time; // ping timer
|
||||
bool pinging; // TRUE if we are doing a ping test with the other modem - to check if it is still present
|
||||
|
||||
bool rx_not_ready_mode; // TRUE if we have told the other modem we cannot receive data (due to buffer filling up).
|
||||
// we set it back to FALSE when our received buffer starts to empty
|
||||
|
||||
volatile int16_t ready_to_send_timer; // ms .. used to hold off packet transmission to wait a bit for data to mount up for transmission (improves data thru-put speed)
|
||||
|
||||
volatile int32_t not_ready_timer; // ms .. >= 0 while we have been asked not to send anymore data to the other modem, -1 when we are allowed to send data
|
||||
|
||||
bool send_encrypted; // TRUE if we are to AES encrypt in every packet we transmit
|
||||
|
||||
int16_t rx_rssi_dBm; // the strength of the received packet
|
||||
int32_t rx_afc_Hz; // the frequency offset of the received packet
|
||||
|
||||
} t_connection;
|
||||
|
||||
// *****************************************************************************
|
||||
|
||||
uint32_t our_serial_number = 0; // our serial number
|
||||
|
||||
t_connection connection[PH_MAX_CONNECTIONS]; // holds each connection state
|
||||
|
||||
uint8_t aes_key[AES_BLOCK_SIZE] __attribute__ ((aligned(4))); // holds the aes encryption key - the same for ALL connections
|
||||
uint8_t dec_aes_key[AES_BLOCK_SIZE] __attribute__ ((aligned(4))); // holds the pre-calculated decryption key
|
||||
uint8_t enc_cbc[AES_BLOCK_SIZE] __attribute__ ((aligned(4))); // holds the tx aes cbc bytes
|
||||
|
||||
uint8_t ph_tx_buffer[256] __attribute__ ((aligned(4))); // holds the transmit packet
|
||||
|
||||
uint8_t ph_rx_buffer[256] __attribute__ ((aligned(4))); // holds the received packet
|
||||
|
||||
int16_t rx_rssi_dBm;
|
||||
int32_t rx_afc_Hz;
|
||||
|
||||
bool fast_ping;
|
||||
|
||||
// *****************************************************************************
|
||||
// return TRUE if we are connected to the remote modem
|
||||
|
||||
bool ph_connected(const int connection_index)
|
||||
{
|
||||
if (connection_index < 0 || connection_index >= PH_MAX_CONNECTIONS)
|
||||
return FALSE;
|
||||
|
||||
t_connection *conn = &connection[connection_index];
|
||||
|
||||
return (conn->link_state == LINK_CONNECTED);
|
||||
}
|
||||
|
||||
// *****************************************************************************
|
||||
// public tx buffer functions
|
||||
|
||||
uint16_t ph_putData_free(const int connection_index)
|
||||
{ // return the free space size
|
||||
if (connection_index < 0 || connection_index >= PH_MAX_CONNECTIONS)
|
||||
return 0;
|
||||
|
||||
return fifoBuf_getFree(&connection[connection_index].tx_fifo_buffer);
|
||||
}
|
||||
|
||||
uint16_t ph_putData(const int connection_index, const void *data, uint16_t len)
|
||||
{ // add data to our tx buffer to be sent
|
||||
if (connection_index < 0 || connection_index >= PH_MAX_CONNECTIONS)
|
||||
return 0;
|
||||
|
||||
return fifoBuf_putData(&connection[connection_index].tx_fifo_buffer, data, len);
|
||||
}
|
||||
|
||||
// *****************************************************************************
|
||||
// public rx buffer functions
|
||||
|
||||
uint16_t ph_getData_used(const int connection_index)
|
||||
{ // return the number of bytes available in the rx buffer
|
||||
if (connection_index < 0 || connection_index >= PH_MAX_CONNECTIONS)
|
||||
return 0;
|
||||
|
||||
return fifoBuf_getUsed(&connection[connection_index].rx_fifo_buffer);
|
||||
}
|
||||
|
||||
uint16_t ph_getData(const int connection_index, void *data, uint16_t len)
|
||||
{ // get data from our rx buffer
|
||||
if (connection_index < 0 || connection_index >= PH_MAX_CONNECTIONS)
|
||||
return 0;
|
||||
|
||||
return fifoBuf_getData(&connection[connection_index].rx_fifo_buffer, data, len);
|
||||
}
|
||||
|
||||
// *****************************************************************************
|
||||
// start a connection to another modem
|
||||
|
||||
int ph_startConnect(int connection_index, uint32_t sn)
|
||||
{
|
||||
random32 = updateCRC32(random32, 0xff);
|
||||
|
||||
if (connection_index < 0 || connection_index >= PH_MAX_CONNECTIONS)
|
||||
return -1;
|
||||
|
||||
t_connection *conn = &connection[connection_index];
|
||||
|
||||
conn->link_state = LINK_DISCONNECTED;
|
||||
|
||||
LINK_LED_OFF;
|
||||
|
||||
conn->serial_number = sn;
|
||||
|
||||
conn->tx_sequence = 0;
|
||||
conn->tx_sequence_data_size = 0;
|
||||
conn->rx_sequence = 0;
|
||||
|
||||
// fifoBuf_init(&conn->tx_fifo_buffer, conn->tx_buffer, PH_FIFO_BUFFER_SIZE);
|
||||
// fifoBuf_init(&conn->rx_fifo_buffer, conn->rx_buffer, PH_FIFO_BUFFER_SIZE);
|
||||
|
||||
conn->tx_packet_timer = 0;
|
||||
|
||||
conn->tx_retry_time_slots = 5;
|
||||
|
||||
uint32_t ms = 1280000ul / rfm22_getDatarate();
|
||||
if (ms < 10) ms = 10;
|
||||
else
|
||||
if (ms > 32000) ms = 32000;
|
||||
conn->tx_retry_time_slot_len = ms;
|
||||
|
||||
conn->tx_retry_time = conn->tx_retry_time_slot_len * 4 + (random32 % conn->tx_retry_time_slots) * conn->tx_retry_time_slot_len * 4;
|
||||
|
||||
conn->tx_retry_counter = 0;
|
||||
|
||||
conn->data_speed_timer = 0;
|
||||
conn->tx_data_speed_count = 0;
|
||||
conn->tx_data_speed = 0;
|
||||
conn->rx_data_speed_count = 0;
|
||||
conn->rx_data_speed = 0;
|
||||
|
||||
conn->ping_time = 8000 + (random32 % 100) * 10;
|
||||
conn->fast_ping_time = 600 + (random32 % 50) * 10;
|
||||
conn->pinging = false;
|
||||
|
||||
conn->rx_not_ready_mode = false;
|
||||
|
||||
conn->ready_to_send_timer = -1;
|
||||
|
||||
conn->not_ready_timer = -1;
|
||||
|
||||
// conn->send_encrypted = true;
|
||||
// conn->send_encrypted = false;
|
||||
|
||||
conn->rx_rssi_dBm = -200;
|
||||
conn->rx_afc_Hz = 0;
|
||||
|
||||
if (sn != 0 && sn == our_serial_number)
|
||||
return -2; // same as our own
|
||||
|
||||
if (sn == BROADCAST_ADDR)
|
||||
{
|
||||
|
||||
return -3;
|
||||
}
|
||||
|
||||
if (conn->serial_number != 0)
|
||||
conn->link_state = LINK_CONNECTING;
|
||||
|
||||
return connection_index;
|
||||
}
|
||||
|
||||
// *****************************************************************************
|
||||
// return a byte for the tx packet transmission.
|
||||
//
|
||||
// return value < 0 if no more bytes available, otherwise return byte to be sent
|
||||
|
||||
int16_t ph_TxDataByteCallback(void)
|
||||
{
|
||||
return -1;
|
||||
}
|
||||
|
||||
// *************************************************************
|
||||
// we are being given a block of received bytes
|
||||
//
|
||||
// return TRUE to continue current packet receive, otherwise return FALSE to halt current packet reception
|
||||
|
||||
bool ph_RxDataCallback(void *data, uint8_t len)
|
||||
{
|
||||
return true;
|
||||
}
|
||||
|
||||
// *****************************************************************************
|
||||
// transmit a packet
|
||||
|
||||
bool ph_sendPacket(int connection_index, bool encrypt, uint8_t packet_type, bool send_immediately)
|
||||
{
|
||||
uint8_t key[AES_BLOCK_SIZE];
|
||||
|
||||
t_connection *conn = NULL;
|
||||
|
||||
// ***********
|
||||
|
||||
t_encrypted_packet *encrypted_packet = (t_encrypted_packet*)&ph_tx_buffer; // point to the tx buffer
|
||||
t_unencrypted_packet *unencrypted_packet = (t_unencrypted_packet*)&ph_tx_buffer; // point to the tx buffer
|
||||
|
||||
t_packet_header *header;
|
||||
uint8_t *data;
|
||||
uint16_t max_data_size;
|
||||
|
||||
if (encrypt)
|
||||
{
|
||||
header = (t_packet_header *)&encrypted_packet->header;
|
||||
data = (uint8_t *)&encrypted_packet->data;
|
||||
max_data_size = sizeof(encrypted_packet->data);
|
||||
}
|
||||
else
|
||||
{
|
||||
header = (t_packet_header *)&unencrypted_packet->header;
|
||||
data = (uint8_t *)&unencrypted_packet->data;
|
||||
max_data_size = sizeof(unencrypted_packet->data);
|
||||
}
|
||||
|
||||
// ***********
|
||||
|
||||
if (!rfm22_txReady())
|
||||
return false;
|
||||
|
||||
if ((packet_type & PACKET_TYPE_MASK) == PACKET_TYPE_NONE)
|
||||
return false;
|
||||
|
||||
if (connection_index >= PH_MAX_CONNECTIONS)
|
||||
return false;
|
||||
|
||||
if (connection_index >= 0)
|
||||
conn = (t_connection *)&connection[connection_index];
|
||||
else
|
||||
return false;
|
||||
|
||||
// ******************
|
||||
// stuff
|
||||
|
||||
uint8_t pack_type = packet_type & PACKET_TYPE_MASK;
|
||||
|
||||
bool data_packet = (pack_type == PACKET_TYPE_DATA || pack_type == PACKET_TYPE_NOTREADY);
|
||||
|
||||
// ******************
|
||||
// calculate how many user data bytes we are going to add to the packet
|
||||
|
||||
uint16_t data_size = 0;
|
||||
|
||||
if (data_packet && conn)
|
||||
{ // we're adding user data to the packet
|
||||
data_size = fifoBuf_getUsed(&connection[connection_index].tx_fifo_buffer); // the number of data bytes waiting to be sent
|
||||
|
||||
if (data_size > max_data_size)
|
||||
data_size = max_data_size;
|
||||
|
||||
if (conn->tx_sequence_data_size > 0)
|
||||
{ // we are re-sending data the same data
|
||||
if (data_size > conn->tx_sequence_data_size)
|
||||
data_size = conn->tx_sequence_data_size;
|
||||
}
|
||||
}
|
||||
|
||||
// ******************
|
||||
// calculate the total packet size (including null data bytes if we have to add null data byte in AES encrypted packets)
|
||||
|
||||
uint32_t packet_size;
|
||||
|
||||
if (encrypt)
|
||||
{
|
||||
packet_size = AES_BLOCK_SIZE + sizeof(t_packet_header) + data_size;
|
||||
|
||||
// total packet size must be a multiple of 'AES_BLOCK_SIZE' bytes - aes encryption works on 16-byte blocks
|
||||
packet_size = (packet_size + (AES_BLOCK_SIZE - 1)) & ~(AES_BLOCK_SIZE - 1);
|
||||
}
|
||||
else
|
||||
{
|
||||
packet_size = 1 + sizeof(t_packet_header) + data_size;
|
||||
}
|
||||
|
||||
// ******************
|
||||
// construct the packets entire header
|
||||
|
||||
if (encrypt)
|
||||
{
|
||||
memmove(key, aes_key, sizeof(key)); // fetch the encryption key
|
||||
aes_encrypt_cbc_128(enc_cbc, key, NULL); // help randomize the CBC bytes
|
||||
|
||||
// ensure the 1st byte is not zero - to indicate this packet is encrypted
|
||||
while (enc_cbc[0] == 0)
|
||||
{
|
||||
random32 = updateCRC32(random32, 0xff);
|
||||
enc_cbc[0] ^= random32;
|
||||
}
|
||||
|
||||
memmove(encrypted_packet->cbc, enc_cbc, AES_BLOCK_SIZE); // copy the AES CBC bytes into the packet
|
||||
}
|
||||
else
|
||||
unencrypted_packet->null_byte = 0; // packet is not encrypted
|
||||
|
||||
header->source_id = our_serial_number; // our serial number
|
||||
// header->destination_id = BROADCAST_ADDR; // broadcast packet
|
||||
header->destination_id = conn->serial_number; // the other modems serial number
|
||||
header->type = packet_type; // packet type
|
||||
header->tx_seq = conn->tx_sequence; // our TX sequence number
|
||||
header->rx_seq = conn->rx_sequence; // our RX sequence number
|
||||
header->data_size = data_size; // the number of user data bytes in the packet
|
||||
header->crc = 0; // the CRC of the header and user data bytes
|
||||
|
||||
// ******************
|
||||
// add the user data to the packet
|
||||
|
||||
if (data_packet)
|
||||
{ // we're adding user data to the packet
|
||||
fifoBuf_getDataPeek(&connection[connection_index].tx_fifo_buffer, data, data_size);
|
||||
|
||||
if (encrypt)
|
||||
{ // zero unused bytes
|
||||
if (data_size < max_data_size)
|
||||
memset(data + data_size, 0, max_data_size - data_size);
|
||||
}
|
||||
|
||||
conn->tx_sequence_data_size = data_size; // remember how much data we are sending in this packet
|
||||
}
|
||||
|
||||
// ******************
|
||||
// complete the packet header by adding the CRC
|
||||
|
||||
if (encrypt)
|
||||
header->crc = updateCRC32Data(0xffffffff, header, packet_size - AES_BLOCK_SIZE);
|
||||
else
|
||||
header->crc = updateCRC32Data(0xffffffff, header, packet_size - 1);
|
||||
|
||||
// ******************
|
||||
// encrypt the packet
|
||||
|
||||
if (encrypt)
|
||||
{ // encrypt the packet .. 'AES_BLOCK_SIZE' bytes at a time
|
||||
uint8_t *p = (uint8_t *)encrypted_packet;
|
||||
|
||||
// encrypt the cbc
|
||||
memmove(key, aes_key, sizeof(key)); // fetch the encryption key
|
||||
aes_encrypt_cbc_128(p, key, NULL); // encrypt block of data (the CBC bytes)
|
||||
p += AES_BLOCK_SIZE;
|
||||
|
||||
// encrypt the rest of the packet
|
||||
for (uint16_t i = AES_BLOCK_SIZE; i < packet_size; i += AES_BLOCK_SIZE)
|
||||
{
|
||||
memmove(key, aes_key, sizeof(key)); // fetch the encryption key
|
||||
aes_encrypt_cbc_128(p, key, enc_cbc); // encrypt block of data
|
||||
p += AES_BLOCK_SIZE;
|
||||
}
|
||||
}
|
||||
|
||||
// ******************
|
||||
// send the packet
|
||||
|
||||
int32_t res = rfm22_sendData(&ph_tx_buffer, packet_size, send_immediately);
|
||||
|
||||
// ******************
|
||||
|
||||
if (data_size > 0 && conn->tx_retry_counter == 0)
|
||||
conn->tx_data_speed_count += data_size * 8; // + the number of data bits we just sent .. used for calculating the transmit data rate
|
||||
|
||||
// ******************
|
||||
// debug stuff
|
||||
|
||||
#if defined(PACKET_DEBUG)
|
||||
|
||||
DEBUG_PRINTF("T-PACK ");
|
||||
switch (pack_type)
|
||||
{
|
||||
case PACKET_TYPE_NONE: DEBUG_PRINTF("none"); break;
|
||||
case PACKET_TYPE_CONNECT: DEBUG_PRINTF("connect"); break;
|
||||
case PACKET_TYPE_CONNECT_ACK: DEBUG_PRINTF("connect_ack"); break;
|
||||
case PACKET_TYPE_DISCONNECT: DEBUG_PRINTF("disconnect"); break;
|
||||
case PACKET_TYPE_DATA: DEBUG_PRINTF("data"); break;
|
||||
case PACKET_TYPE_DATA_ACK: DEBUG_PRINTF("data_ack"); break;
|
||||
case PACKET_TYPE_READY: DEBUG_PRINTF("ready"); break;
|
||||
case PACKET_TYPE_READY_ACK: DEBUG_PRINTF("ready_ack"); break;
|
||||
case PACKET_TYPE_NOTREADY: DEBUG_PRINTF("notready"); break;
|
||||
case PACKET_TYPE_NOTREADY_ACK: DEBUG_PRINTF("notready_ack"); break;
|
||||
case PACKET_TYPE_DATARATE: DEBUG_PRINTF("datarate"); break;
|
||||
case PACKET_TYPE_DATARATE_ACK: DEBUG_PRINTF("datarate_ack"); break;
|
||||
case PACKET_TYPE_PING: DEBUG_PRINTF("ping"); break;
|
||||
case PACKET_TYPE_PONG: DEBUG_PRINTF("pong"); break;
|
||||
case PACKET_TYPE_ADJUST_TX_PWR: DEBUG_PRINTF("PACKET_TYPE_ADJUST_TX_PWR"); break;
|
||||
case PACKET_TYPE_ADJUST_TX_PWR_ACK: DEBUG_PRINTF("PACKET_TYPE_ADJUST_TX_PWR_ACK"); break;
|
||||
default: DEBUG_PRINTF("UNKNOWN [%d]", pack_type); break;
|
||||
}
|
||||
DEBUG_PRINTF(" tseq:%d rseq:%d", conn->tx_sequence, conn->rx_sequence);
|
||||
DEBUG_PRINTF(" drate:%dbps", conn->tx_data_speed);
|
||||
if (data_size > 0) DEBUG_PRINTF(" data_size:%d", data_size);
|
||||
if (conn->tx_retry_counter > 0) DEBUG_PRINTF(" retry:%d", conn->tx_retry_counter);
|
||||
DEBUG_PRINTF("\r\n");
|
||||
#endif
|
||||
|
||||
// ******************
|
||||
|
||||
switch (pack_type)
|
||||
{
|
||||
case PACKET_TYPE_CONNECT:
|
||||
case PACKET_TYPE_DISCONNECT:
|
||||
case PACKET_TYPE_DATA:
|
||||
case PACKET_TYPE_READY:
|
||||
case PACKET_TYPE_NOTREADY:
|
||||
case PACKET_TYPE_DATARATE:
|
||||
case PACKET_TYPE_PING:
|
||||
case PACKET_TYPE_ADJUST_TX_PWR:
|
||||
if (conn->tx_retry_counter < 0xffff)
|
||||
conn->tx_retry_counter++;
|
||||
break;
|
||||
|
||||
case PACKET_TYPE_CONNECT_ACK:
|
||||
case PACKET_TYPE_DATA_ACK:
|
||||
case PACKET_TYPE_READY_ACK:
|
||||
case PACKET_TYPE_NOTREADY_ACK:
|
||||
case PACKET_TYPE_DATARATE_ACK:
|
||||
case PACKET_TYPE_PONG:
|
||||
case PACKET_TYPE_ADJUST_TX_PWR_ACK:
|
||||
break;
|
||||
|
||||
case PACKET_TYPE_NONE:
|
||||
break;
|
||||
}
|
||||
|
||||
return (res >= packet_size);
|
||||
}
|
||||
|
||||
// *****************************************************************************
|
||||
|
||||
void ph_processPacket2(bool was_encrypted, t_packet_header *header, uint8_t *data)
|
||||
{ // process the received decrypted error-free packet
|
||||
|
||||
USB_LED_TOGGLE; // TEST ONLY
|
||||
|
||||
// ***********
|
||||
|
||||
// fetch the data compressed bit
|
||||
bool compressed_data = (header->type & PACKET_TYPE_DATA_COMP_BIT) != 0;
|
||||
|
||||
// fetch the packet type
|
||||
uint8_t packet_type = header->type & PACKET_TYPE_MASK;
|
||||
|
||||
// fetch the number of data bytes in the packet
|
||||
uint16_t data_size = header->data_size;
|
||||
|
||||
// update the ramdon number
|
||||
random32 = updateCRC32(random32, 0xff);
|
||||
|
||||
// *********************
|
||||
// debug stuff
|
||||
/*
|
||||
#if defined(PACKET_DEBUG)
|
||||
if (data_size > 0)
|
||||
{
|
||||
DEBUG_PRINTF("rx packet:");
|
||||
for (uint16_t i = 0; i < data_size; i++)
|
||||
DEBUG_PRINTF(" %u", data[i]);
|
||||
DEBUG_PRINTF("\r\n");
|
||||
}
|
||||
#endif
|
||||
*/
|
||||
// ***********
|
||||
// debug stuff
|
||||
|
||||
#if defined(PACKET_DEBUG)
|
||||
DEBUG_PRINTF("R-PACK ");
|
||||
switch (packet_type)
|
||||
{
|
||||
case PACKET_TYPE_NONE: DEBUG_PRINTF("none"); break;
|
||||
case PACKET_TYPE_CONNECT: DEBUG_PRINTF("connect"); break;
|
||||
case PACKET_TYPE_CONNECT_ACK: DEBUG_PRINTF("connect_ack"); break;
|
||||
case PACKET_TYPE_DISCONNECT: DEBUG_PRINTF("disconnect"); break;
|
||||
case PACKET_TYPE_DATA: DEBUG_PRINTF("data"); break;
|
||||
case PACKET_TYPE_DATA_ACK: DEBUG_PRINTF("data_ack"); break;
|
||||
case PACKET_TYPE_READY: DEBUG_PRINTF("ready"); break;
|
||||
case PACKET_TYPE_READY_ACK: DEBUG_PRINTF("ready_ack"); break;
|
||||
case PACKET_TYPE_NOTREADY: DEBUG_PRINTF("notready"); break;
|
||||
case PACKET_TYPE_NOTREADY_ACK: DEBUG_PRINTF("notready_ack"); break;
|
||||
case PACKET_TYPE_DATARATE: DEBUG_PRINTF("datarate"); break;
|
||||
case PACKET_TYPE_DATARATE_ACK: DEBUG_PRINTF("datarate_ack"); break;
|
||||
case PACKET_TYPE_PING: DEBUG_PRINTF("ping"); break;
|
||||
case PACKET_TYPE_PONG: DEBUG_PRINTF("pong"); break;
|
||||
case PACKET_TYPE_ADJUST_TX_PWR: DEBUG_PRINTF("PACKET_TYPE_ADJUST_TX_PWR"); break;
|
||||
case PACKET_TYPE_ADJUST_TX_PWR_ACK: DEBUG_PRINTF("PACKET_TYPE_ADJUST_TX_PWR_ACK"); break;
|
||||
default: DEBUG_PRINTF("UNKNOWN [%d]", packet_type); break;
|
||||
}
|
||||
DEBUG_PRINTF(" tseq-%d rseq-%d", header->tx_seq, header->rx_seq);
|
||||
// DEBUG_PRINTF(" drate:%dbps", conn->rx_data_speed);
|
||||
if (data_size > 0) DEBUG_PRINTF(" data_size:%d", data_size);
|
||||
DEBUG_PRINTF(" %ddBm", rx_rssi_dBm);
|
||||
DEBUG_PRINTF(" %dHz", rx_afc_Hz);
|
||||
DEBUG_PRINTF("\r\n");
|
||||
#endif
|
||||
|
||||
// *********************
|
||||
|
||||
if (header->source_id == our_serial_number)
|
||||
return; // it's our own packet .. ignore it
|
||||
|
||||
if (header->destination_id == BROADCAST_ADDR)
|
||||
{ // it's a broadcast packet
|
||||
|
||||
|
||||
|
||||
// todo:
|
||||
|
||||
|
||||
|
||||
|
||||
return;
|
||||
}
|
||||
|
||||
if (header->destination_id != our_serial_number)
|
||||
return; // the packet is not meant for us
|
||||
|
||||
// *********************
|
||||
// find out which remote connection this packet is from
|
||||
|
||||
int connection_index = 0;
|
||||
while (connection_index < PH_MAX_CONNECTIONS)
|
||||
{
|
||||
uint32_t sn = connection[connection_index].serial_number;
|
||||
if (sn != 0)
|
||||
{ // connection used
|
||||
if (header->source_id == sn)
|
||||
break; // found it
|
||||
}
|
||||
connection_index++;
|
||||
}
|
||||
|
||||
if (connection_index >= PH_MAX_CONNECTIONS)
|
||||
{ // the packet is from an unknown source ID (unknown modem)
|
||||
|
||||
if (packet_type != PACKET_TYPE_NONE)
|
||||
{ // send a disconnect packet back to them
|
||||
// ph_sendPacket(-1, was_encrypted, PACKET_TYPE_DISCONNECT, true);
|
||||
}
|
||||
|
||||
return;
|
||||
}
|
||||
|
||||
t_connection *conn = &connection[connection_index];
|
||||
|
||||
// ***********
|
||||
|
||||
conn->rx_rssi_dBm = rx_rssi_dBm; // remember the packets signal strength
|
||||
conn->rx_afc_Hz = rx_afc_Hz; // remember the packets frequency offset
|
||||
|
||||
// ***********
|
||||
// decompress the data
|
||||
|
||||
if (compressed_data && data_size > 0)
|
||||
{
|
||||
|
||||
|
||||
// todo:
|
||||
|
||||
|
||||
}
|
||||
|
||||
// ***********
|
||||
|
||||
if (packet_type == PACKET_TYPE_NONE)
|
||||
return;
|
||||
|
||||
if (packet_type == PACKET_TYPE_DISCONNECT)
|
||||
{
|
||||
conn->link_state = LINK_DISCONNECTED;
|
||||
LINK_LED_OFF;
|
||||
return;
|
||||
}
|
||||
|
||||
if (packet_type == PACKET_TYPE_CONNECT)
|
||||
{
|
||||
LINK_LED_ON;
|
||||
|
||||
// fifoBuf_init(&conn->tx_fifo_buffer, conn->tx_buffer, PH_FIFO_BUFFER_SIZE);
|
||||
// fifoBuf_init(&conn->rx_fifo_buffer, conn->rx_buffer, PH_FIFO_BUFFER_SIZE);
|
||||
|
||||
conn->tx_packet_timer = 0;
|
||||
|
||||
conn->tx_retry_counter = 0;
|
||||
conn->tx_retry_time = conn->tx_retry_time_slot_len + (random32 % conn->tx_retry_time_slots) * conn->tx_retry_time_slot_len;
|
||||
|
||||
conn->rx_sequence = header->tx_seq;
|
||||
conn->tx_sequence = 0;
|
||||
conn->tx_sequence_data_size = 0;
|
||||
|
||||
conn->data_speed_timer = 0;
|
||||
conn->tx_data_speed_count = 0;
|
||||
conn->tx_data_speed = 0;
|
||||
conn->rx_data_speed_count = 0;
|
||||
conn->rx_data_speed = 0;
|
||||
|
||||
conn->ping_time = 8000 + (random32 % 100) * 10;
|
||||
conn->fast_ping_time = 600 + (random32 % 50) * 10;
|
||||
conn->pinging = false;
|
||||
|
||||
conn->rx_not_ready_mode = false;
|
||||
|
||||
conn->ready_to_send_timer = -1;
|
||||
|
||||
conn->not_ready_timer = -1;
|
||||
|
||||
conn->link_state = LINK_CONNECTED;
|
||||
|
||||
// send an ack back
|
||||
if (ph_sendPacket(connection_index, conn->send_encrypted, PACKET_TYPE_CONNECT_ACK, true))
|
||||
{
|
||||
conn->tx_packet_timer = 0;
|
||||
}
|
||||
|
||||
return;
|
||||
}
|
||||
|
||||
if (packet_type == PACKET_TYPE_CONNECT_ACK)
|
||||
{
|
||||
LINK_LED_ON;
|
||||
|
||||
if (conn->link_state != LINK_CONNECTING)
|
||||
{ // reset the link
|
||||
ph_set_remote_serial_number(connection_index, conn->serial_number);
|
||||
return;
|
||||
}
|
||||
|
||||
conn->tx_packet_timer = 0;
|
||||
|
||||
conn->tx_retry_counter = 0;
|
||||
conn->tx_retry_time = conn->tx_retry_time_slot_len + (random32 % conn->tx_retry_time_slots) * conn->tx_retry_time_slot_len;
|
||||
|
||||
conn->rx_sequence = header->tx_seq;
|
||||
conn->tx_sequence = 0;
|
||||
conn->tx_sequence_data_size = 0;
|
||||
|
||||
conn->data_speed_timer = 0;
|
||||
conn->tx_data_speed_count = 0;
|
||||
conn->tx_data_speed = 0;
|
||||
conn->rx_data_speed_count = 0;
|
||||
conn->rx_data_speed = 0;
|
||||
|
||||
conn->ping_time = 8000 + (random32 % 100) * 10;
|
||||
conn->fast_ping_time = 600 + (random32 % 50) * 10;
|
||||
conn->pinging = false;
|
||||
|
||||
conn->rx_not_ready_mode = false;
|
||||
|
||||
conn->ready_to_send_timer = -1;
|
||||
|
||||
conn->not_ready_timer = -1;
|
||||
|
||||
conn->link_state = LINK_CONNECTED;
|
||||
|
||||
return;
|
||||
}
|
||||
|
||||
|
||||
|
||||
|
||||
if (conn->link_state == LINK_CONNECTING)
|
||||
{ // we are trying to connect to them .. reply with a connect request packet
|
||||
if (ph_sendPacket(connection_index, conn->send_encrypted, PACKET_TYPE_CONNECT, true))
|
||||
{
|
||||
conn->tx_packet_timer = 0;
|
||||
conn->tx_retry_time = conn->tx_retry_time_slot_len * 4 + (random32 % conn->tx_retry_time_slots) * conn->tx_retry_time_slot_len * 4;
|
||||
}
|
||||
return;
|
||||
}
|
||||
|
||||
if (conn->link_state != LINK_CONNECTED)
|
||||
{ // they have sent us a packet when we are not in a connected state - start a connection
|
||||
ph_startConnect(connection_index, conn->serial_number);
|
||||
return;
|
||||
}
|
||||
|
||||
|
||||
|
||||
|
||||
// check to make sure it's a wanted packet type
|
||||
switch (packet_type)
|
||||
{
|
||||
case PACKET_TYPE_DATA:
|
||||
case PACKET_TYPE_DATA_ACK:
|
||||
case PACKET_TYPE_READY:
|
||||
case PACKET_TYPE_READY_ACK:
|
||||
case PACKET_TYPE_NOTREADY:
|
||||
case PACKET_TYPE_NOTREADY_ACK:
|
||||
case PACKET_TYPE_DATARATE:
|
||||
case PACKET_TYPE_DATARATE_ACK:
|
||||
case PACKET_TYPE_PING:
|
||||
case PACKET_TYPE_PONG:
|
||||
case PACKET_TYPE_ADJUST_TX_PWR:
|
||||
case PACKET_TYPE_ADJUST_TX_PWR_ACK:
|
||||
break;
|
||||
default:
|
||||
return;
|
||||
}
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
if ((conn->tx_sequence_data_size > 0) && (header->rx_seq == (uint8_t)(conn->tx_sequence + 1)))
|
||||
{ // they received our last data packet
|
||||
|
||||
// remove the data we have sent and they have acked
|
||||
fifoBuf_removeData(&conn->tx_fifo_buffer, conn->tx_sequence_data_size);
|
||||
|
||||
conn->tx_sequence++;
|
||||
conn->tx_retry_counter = 0;
|
||||
conn->tx_sequence_data_size = 0;
|
||||
conn->not_ready_timer = -1; // stop timer
|
||||
}
|
||||
|
||||
uint16_t size = fifoBuf_getUsed(&conn->tx_fifo_buffer); // the size of data waiting to be sent
|
||||
|
||||
|
||||
|
||||
|
||||
if (packet_type == PACKET_TYPE_DATA || packet_type == PACKET_TYPE_DATA_ACK)
|
||||
{
|
||||
if (packet_type == PACKET_TYPE_DATA && header->tx_seq == conn->rx_sequence)
|
||||
{ // the packet number is what we expected
|
||||
|
||||
if (data_size > 0)
|
||||
{ // save the data
|
||||
|
||||
conn->rx_data_speed_count += data_size * 8; // + the number of data bits we just received
|
||||
|
||||
uint16_t num = fifoBuf_getFree(&conn->rx_fifo_buffer);
|
||||
if (num < data_size)
|
||||
{ // error .. we don't have enough space left in our fifo buffer to save the data .. discard it and tell them to hold off a sec
|
||||
// conn->rx_not_ready_mode = true;
|
||||
}
|
||||
else
|
||||
{ // save the received data into our fifo buffer
|
||||
fifoBuf_putData(&conn->rx_fifo_buffer, data, data_size);
|
||||
conn->rx_sequence++;
|
||||
conn->rx_not_ready_mode = false;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
if (size >= 200 || (conn->ready_to_send_timer >= 10 && size > 0) || (conn->tx_sequence_data_size > 0 && size > 0))
|
||||
{ // send data
|
||||
uint8_t pack_type = PACKET_TYPE_DATA;
|
||||
if (conn->rx_not_ready_mode)
|
||||
pack_type = PACKET_TYPE_NOTREADY;
|
||||
|
||||
if (ph_sendPacket(connection_index, conn->send_encrypted, pack_type, true))
|
||||
{
|
||||
conn->tx_packet_timer = 0;
|
||||
conn->tx_retry_time = conn->tx_retry_time_slot_len + (random32 % conn->tx_retry_time_slots) * conn->tx_retry_time_slot_len;
|
||||
return;
|
||||
}
|
||||
}
|
||||
|
||||
if (packet_type == PACKET_TYPE_DATA)
|
||||
{ // send an ack back
|
||||
uint8_t pack_type = PACKET_TYPE_DATA_ACK;
|
||||
if (conn->rx_not_ready_mode)
|
||||
pack_type = PACKET_TYPE_NOTREADY_ACK;
|
||||
|
||||
if (ph_sendPacket(connection_index, conn->send_encrypted, pack_type, true))
|
||||
{
|
||||
conn->tx_packet_timer = 0;
|
||||
conn->tx_retry_time = conn->tx_retry_time_slot_len + (random32 % conn->tx_retry_time_slots) * conn->tx_retry_time_slot_len;
|
||||
return;
|
||||
}
|
||||
}
|
||||
|
||||
return;
|
||||
}
|
||||
|
||||
if (packet_type == PACKET_TYPE_READY)
|
||||
{
|
||||
conn->not_ready_timer = -1; // stop timer
|
||||
|
||||
// send an ack back
|
||||
if (ph_sendPacket(connection_index, conn->send_encrypted, PACKET_TYPE_READY_ACK, true))
|
||||
{
|
||||
conn->tx_packet_timer = 0;
|
||||
conn->tx_retry_time = conn->tx_retry_time_slot_len * 4 + (random32 % conn->tx_retry_time_slots) * conn->tx_retry_time_slot_len * 4;
|
||||
return;
|
||||
}
|
||||
|
||||
return;
|
||||
}
|
||||
|
||||
if (packet_type == PACKET_TYPE_READY_ACK)
|
||||
{
|
||||
conn->rx_not_ready_mode = false;
|
||||
return;
|
||||
}
|
||||
|
||||
if (packet_type == PACKET_TYPE_NOTREADY)
|
||||
{
|
||||
// conn->not_ready_timer = 0; // start timer
|
||||
|
||||
if (header->tx_seq == conn->rx_sequence)
|
||||
{ // the packet number is what we expected
|
||||
|
||||
if (data_size > 0)
|
||||
{ // save the data
|
||||
|
||||
conn->rx_data_speed_count += data_size * 8; // + the number of data bits we just received
|
||||
|
||||
uint16_t num = fifoBuf_getFree(&conn->rx_fifo_buffer);
|
||||
if (num < data_size)
|
||||
{ // error .. we don't have enough space left in our fifo buffer to save the data .. discard it and tell them to hold off a sec
|
||||
// conn->rx_not_ready_mode = true;
|
||||
}
|
||||
else
|
||||
{ // save the received data into our fifo buffer
|
||||
fifoBuf_putData(&conn->rx_fifo_buffer, data, data_size);
|
||||
conn->rx_sequence++;
|
||||
conn->rx_not_ready_mode = false;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// send an ack back
|
||||
if (ph_sendPacket(connection_index, conn->send_encrypted, PACKET_TYPE_NOTREADY_ACK, true))
|
||||
{
|
||||
conn->tx_packet_timer = 0;
|
||||
conn->tx_retry_time = conn->tx_retry_time_slot_len * 4 + (random32 % conn->tx_retry_time_slots) * conn->tx_retry_time_slot_len * 4;
|
||||
return;
|
||||
}
|
||||
|
||||
return;
|
||||
}
|
||||
|
||||
if (packet_type == PACKET_TYPE_NOTREADY_ACK)
|
||||
{
|
||||
return;
|
||||
}
|
||||
|
||||
if (packet_type == PACKET_TYPE_PING)
|
||||
{ // send a pong back
|
||||
if (ph_sendPacket(connection_index, conn->send_encrypted, PACKET_TYPE_PONG, true))
|
||||
{
|
||||
conn->tx_packet_timer = 0;
|
||||
conn->tx_retry_time = conn->tx_retry_time_slot_len + (random32 % conn->tx_retry_time_slots) * conn->tx_retry_time_slot_len;
|
||||
}
|
||||
return;
|
||||
}
|
||||
|
||||
if (packet_type == PACKET_TYPE_PONG)
|
||||
{
|
||||
if (conn->pinging)
|
||||
{
|
||||
conn->pinging = false;
|
||||
conn->tx_retry_counter = 0;
|
||||
}
|
||||
return;
|
||||
}
|
||||
|
||||
if (packet_type == PACKET_TYPE_DATARATE)
|
||||
{
|
||||
// send an ack back
|
||||
if (ph_sendPacket(connection_index, conn->send_encrypted, PACKET_TYPE_DATARATE_ACK, true))
|
||||
{
|
||||
conn->tx_packet_timer = 0;
|
||||
conn->tx_retry_time = conn->tx_retry_time_slot_len + (random32 % conn->tx_retry_time_slots) * conn->tx_retry_time_slot_len;
|
||||
}
|
||||
return;
|
||||
}
|
||||
|
||||
if (packet_type == PACKET_TYPE_DATARATE_ACK)
|
||||
{
|
||||
return;
|
||||
}
|
||||
|
||||
if (packet_type == PACKET_TYPE_ADJUST_TX_PWR)
|
||||
{
|
||||
// send an ack back
|
||||
if (ph_sendPacket(connection_index, conn->send_encrypted, PACKET_TYPE_ADJUST_TX_PWR_ACK, true))
|
||||
{
|
||||
conn->tx_packet_timer = 0;
|
||||
conn->tx_retry_time = conn->tx_retry_time_slot_len + (random32 % conn->tx_retry_time_slots) * conn->tx_retry_time_slot_len;
|
||||
}
|
||||
return;
|
||||
}
|
||||
|
||||
if (packet_type == PACKET_TYPE_ADJUST_TX_PWR_ACK)
|
||||
{
|
||||
return;
|
||||
}
|
||||
|
||||
// *********************
|
||||
}
|
||||
|
||||
void ph_processRxPacket(void)
|
||||
{
|
||||
uint32_t crc1, crc2;
|
||||
uint8_t key[AES_BLOCK_SIZE];
|
||||
register uint8_t *p;
|
||||
|
||||
// ***********
|
||||
// fetch the received packet
|
||||
|
||||
uint16_t packet_size = rfm22_receivedLength();
|
||||
if (packet_size == 0)
|
||||
return; // nothing received
|
||||
|
||||
if (packet_size > sizeof(ph_rx_buffer))
|
||||
{ // packet too big .. discard it
|
||||
rfm22_receivedDone();
|
||||
return;
|
||||
}
|
||||
|
||||
rx_rssi_dBm = rfm22_receivedRSSI(); // fetch the packets signal stength
|
||||
rx_afc_Hz = rfm22_receivedAFCHz(); // fetch the packets frequency offset
|
||||
|
||||
// copy the received packet into our own buffer
|
||||
memmove(ph_rx_buffer, rfm22_receivedPointer(), packet_size);
|
||||
|
||||
rfm22_receivedDone(); // the received packet has been saved
|
||||
|
||||
// *********************
|
||||
// if the 1st byte in the packet is not zero, then the packet is encrypted
|
||||
|
||||
bool encrypted = (ph_rx_buffer[0] != 0);
|
||||
|
||||
// ***********
|
||||
|
||||
t_encrypted_packet *encrypted_packet = (t_encrypted_packet *)&ph_rx_buffer; // point to the rx buffer
|
||||
t_unencrypted_packet *unencrypted_packet = (t_unencrypted_packet *)&ph_rx_buffer; // point to the rx buffer
|
||||
|
||||
t_packet_header *header;
|
||||
uint8_t *data;
|
||||
uint16_t min_packet_size;
|
||||
uint16_t max_data_size;
|
||||
|
||||
if (encrypted)
|
||||
{
|
||||
header = (t_packet_header *)&encrypted_packet->header;
|
||||
data = (uint8_t *)&encrypted_packet->data;
|
||||
min_packet_size = AES_BLOCK_SIZE + sizeof(t_packet_header);
|
||||
max_data_size = sizeof(encrypted_packet->data);
|
||||
}
|
||||
else
|
||||
{
|
||||
header = (t_packet_header *)&unencrypted_packet->header;
|
||||
data = (uint8_t *)&unencrypted_packet->data;
|
||||
min_packet_size = 1 + sizeof(t_packet_header);
|
||||
max_data_size = sizeof(unencrypted_packet->data);
|
||||
}
|
||||
|
||||
if (packet_size < min_packet_size)
|
||||
{ // packet too small .. discard it
|
||||
return;
|
||||
}
|
||||
|
||||
random32 = updateCRC32(random32 ^ header->crc, 0xff); // help randomize the random number
|
||||
|
||||
// *********************
|
||||
// help to randomize the tx aes cbc bytes by using the received packet
|
||||
|
||||
p = (uint8_t *)&ph_rx_buffer;
|
||||
for (uint16_t i = 0; i < packet_size; i += AES_BLOCK_SIZE)
|
||||
{
|
||||
for (int j = AES_BLOCK_SIZE - 1; j >= 0; j--)
|
||||
enc_cbc[j] ^= *p++;
|
||||
}
|
||||
|
||||
// *********************
|
||||
// check the packet size
|
||||
|
||||
if (encrypted)
|
||||
{
|
||||
if ((packet_size & (AES_BLOCK_SIZE - 1)) != 0)
|
||||
return; // packet must be a multiple of 'AES_BLOCK_SIZE' bytes in length - for the aes decryption
|
||||
}
|
||||
|
||||
// *********************
|
||||
// decrypt the packet
|
||||
|
||||
if (encrypted)
|
||||
{
|
||||
p = (uint8_t *)encrypted_packet; // point to the received packet
|
||||
|
||||
// decrypt the cbc
|
||||
memmove(key, (void *)dec_aes_key, sizeof(key)); // fetch the decryption key
|
||||
aes_decrypt_cbc_128(p, key, NULL); // decrypt the cbc bytes
|
||||
p += AES_BLOCK_SIZE;
|
||||
|
||||
// decrypt the rest of the packet
|
||||
for (uint16_t i = AES_BLOCK_SIZE; i < packet_size; i += AES_BLOCK_SIZE)
|
||||
{
|
||||
memmove(key, (void *)dec_aes_key, sizeof(key)); // fetch the decryption key
|
||||
aes_decrypt_cbc_128(p, key, (void *)encrypted_packet->cbc);
|
||||
p += AES_BLOCK_SIZE;
|
||||
}
|
||||
}
|
||||
|
||||
// *********************
|
||||
|
||||
#if defined(PACKET_DEBUG)
|
||||
DEBUG_PRINTF("rx packet: ");
|
||||
DEBUG_PRINTF("%s", encrypted ? "encrypted " : "unencrypted");
|
||||
if (encrypted)
|
||||
{
|
||||
for (int i = 0; i < AES_BLOCK_SIZE; i++)
|
||||
DEBUG_PRINTF("%02X", encrypted_packet->cbc[i]);
|
||||
}
|
||||
DEBUG_PRINTF(" %08X %08X %u %u %u %u %08X\r\n",
|
||||
header->source_id,
|
||||
header->destination_id,
|
||||
header->type,
|
||||
header->tx_seq,
|
||||
header->rx_seq,
|
||||
header->data_size,
|
||||
header->crc);
|
||||
|
||||
if (header->data_size > 0)
|
||||
{
|
||||
DEBUG_PRINTF("rx packet [%u]: ", header->data_size);
|
||||
for (int i = 0; i < header->data_size; i++)
|
||||
DEBUG_PRINTF("%02X", data[i]);
|
||||
DEBUG_PRINTF("\r\n");
|
||||
}
|
||||
#endif
|
||||
|
||||
// *********************
|
||||
|
||||
uint32_t data_size = header->data_size;
|
||||
|
||||
if (packet_size < (min_packet_size + data_size))
|
||||
return; // packet too small
|
||||
|
||||
#if defined(PACKET_DEBUG)
|
||||
// DEBUG_PRINTF("rx packet size: %d\r\n", packet_size);
|
||||
#endif
|
||||
|
||||
// *********************
|
||||
// check the packet is error free
|
||||
|
||||
crc1 = header->crc;
|
||||
header->crc = 0;
|
||||
if (encrypted)
|
||||
crc2 = updateCRC32Data(0xffffffff, header, packet_size - AES_BLOCK_SIZE);
|
||||
else
|
||||
crc2 = updateCRC32Data(0xffffffff, header, packet_size - 1);
|
||||
if (crc1 != crc2)
|
||||
{ // corrupt packet
|
||||
#if defined(PACKET_DEBUG)
|
||||
if (encrypted)
|
||||
DEBUG_PRINTF("ENC-R-PACK corrupt %08X %08X\r\n", crc1, crc2);
|
||||
else
|
||||
DEBUG_PRINTF("R-PACK corrupt %08X %08X\r\n", crc1, crc2);
|
||||
#endif
|
||||
return;
|
||||
}
|
||||
|
||||
// *********************
|
||||
// process the data
|
||||
|
||||
ph_processPacket2(encrypted, header, data);
|
||||
|
||||
// *********************
|
||||
}
|
||||
|
||||
// *****************************************************************************
|
||||
// do all the link/packet handling stuff - request connection/disconnection, send data, acks etc
|
||||
|
||||
void ph_processLinks(int connection_index)
|
||||
{
|
||||
if (connection_index < 0 || connection_index >= PH_MAX_CONNECTIONS)
|
||||
return;
|
||||
|
||||
random32 = updateCRC32(random32, 0xff);
|
||||
|
||||
t_connection *conn = &connection[connection_index];
|
||||
|
||||
bool canTx = (!rfm22_transmitting() && rfm22_channelIsClear());// TRUE is we can transmit
|
||||
|
||||
bool timeToRetry = (rfm22_txReady() && conn->tx_packet_timer >= conn->tx_retry_time);
|
||||
|
||||
bool tomanyRetries = (conn->tx_retry_counter >= RETRY_RECONNECT_COUNT);
|
||||
|
||||
if (conn->tx_retry_counter > 3)
|
||||
conn->rx_rssi_dBm = -200;
|
||||
|
||||
switch (conn->link_state)
|
||||
{
|
||||
case LINK_DISCONNECTED:
|
||||
if (!canTx)
|
||||
{
|
||||
conn->tx_packet_timer = 0;
|
||||
break;
|
||||
}
|
||||
|
||||
if (!rfm22_txReady() || conn->tx_packet_timer < 60000)
|
||||
break;
|
||||
|
||||
if (our_serial_number != 0 && conn->serial_number != 0)
|
||||
{ // try to reconnect with the remote modem
|
||||
ph_startConnect(connection_index, conn->serial_number);
|
||||
break;
|
||||
}
|
||||
|
||||
break;
|
||||
|
||||
case LINK_CONNECTING:
|
||||
if (!canTx)
|
||||
{
|
||||
conn->tx_packet_timer = 0;
|
||||
break;
|
||||
}
|
||||
|
||||
if (!timeToRetry)
|
||||
break;
|
||||
|
||||
if (ph_sendPacket(connection_index, conn->send_encrypted, PACKET_TYPE_CONNECT, false))
|
||||
{
|
||||
conn->tx_packet_timer = 0;
|
||||
conn->tx_retry_time = conn->tx_retry_time_slot_len * 4 + (random32 % conn->tx_retry_time_slots) * conn->tx_retry_time_slot_len * 4;
|
||||
break;
|
||||
}
|
||||
|
||||
break;
|
||||
|
||||
case LINK_CONNECTED:
|
||||
if (!canTx)
|
||||
{
|
||||
conn->tx_packet_timer = 0;
|
||||
break;
|
||||
}
|
||||
|
||||
if (!timeToRetry)
|
||||
break;
|
||||
|
||||
if (tomanyRetries)
|
||||
{ // reset the link if we have sent tomany retries
|
||||
ph_startConnect(connection_index, conn->serial_number);
|
||||
break;
|
||||
}
|
||||
|
||||
if (conn->pinging)
|
||||
{ // we are trying to ping them
|
||||
if (ph_sendPacket(connection_index, conn->send_encrypted, PACKET_TYPE_PING, false))
|
||||
{
|
||||
conn->tx_packet_timer = 0;
|
||||
conn->tx_retry_time = conn->tx_retry_time_slot_len * 4 + (random32 % conn->tx_retry_time_slots) * conn->tx_retry_time_slot_len * 4;
|
||||
}
|
||||
break;
|
||||
}
|
||||
|
||||
uint16_t ping_time = conn->ping_time;
|
||||
if (fast_ping) ping_time = conn->fast_ping_time;
|
||||
if (conn->tx_packet_timer >= ping_time)
|
||||
{ // start pinging
|
||||
if (ph_sendPacket(connection_index, conn->send_encrypted, PACKET_TYPE_PING, false))
|
||||
{
|
||||
conn->ping_time = 8000 + (random32 % 100) * 10;
|
||||
conn->fast_ping_time = 600 + (random32 % 50) * 10;
|
||||
conn->tx_packet_timer = 0;
|
||||
conn->tx_retry_time = conn->tx_retry_time_slot_len * 4 + (random32 % conn->tx_retry_time_slots) * conn->tx_retry_time_slot_len * 4;
|
||||
conn->pinging = true;
|
||||
}
|
||||
break;
|
||||
}
|
||||
|
||||
// ***********
|
||||
// exit rx not ready mode if we have space in our rx buffer for more data
|
||||
/*
|
||||
if (conn->rx_not_ready_mode)
|
||||
{
|
||||
uint16_t size = fifoBuf_getFree(&conn->rx_fifo_buffer);
|
||||
if (size >= conn->rx_fifo_buffer.buf_size / 6)
|
||||
{ // leave 'rx not ready' mode
|
||||
if (ph_sendPacket(connection_index, conn->send_encrypted, PACKET_TYPE_READY, false))
|
||||
{
|
||||
conn->tx_packet_timer = 0;
|
||||
conn->tx_retry_time = conn->tx_retry_time_slot_len + (random32 % conn->tx_retry_time_slots) * conn->tx_retry_time_slot_len;
|
||||
break;
|
||||
}
|
||||
}
|
||||
}
|
||||
*/
|
||||
// ***********
|
||||
// send data packets
|
||||
|
||||
// if (conn->not_ready_timer < 0)
|
||||
{
|
||||
uint16_t size = fifoBuf_getUsed(&conn->tx_fifo_buffer);
|
||||
|
||||
if (size == 0)
|
||||
conn->ready_to_send_timer = -1; // no data to send
|
||||
else
|
||||
if (conn->ready_to_send_timer < 0)
|
||||
conn->ready_to_send_timer = 0; // start timer
|
||||
|
||||
if (size >= 200 || (conn->ready_to_send_timer >= saved_settings.rts_time && size > 0) || (conn->tx_sequence_data_size > 0 && size > 0))
|
||||
{ // send data
|
||||
|
||||
uint8_t pack_type = PACKET_TYPE_DATA;
|
||||
if (conn->rx_not_ready_mode)
|
||||
pack_type = PACKET_TYPE_NOTREADY;
|
||||
|
||||
if (ph_sendPacket(connection_index, conn->send_encrypted, pack_type, false))
|
||||
{
|
||||
conn->tx_packet_timer = 0;
|
||||
conn->tx_retry_time = conn->tx_retry_time_slot_len + (random32 % conn->tx_retry_time_slots) * conn->tx_retry_time_slot_len;
|
||||
}
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
// ***********
|
||||
|
||||
break;
|
||||
|
||||
default: // we should never end up here - maybe we should do a reboot?
|
||||
conn->link_state = LINK_DISCONNECTED;
|
||||
/*
|
||||
// disable all interrupts
|
||||
PIOS_IRQ_Disable();
|
||||
|
||||
// turn off all leds
|
||||
USB_LED_OFF;
|
||||
LINK_LED_OFF;
|
||||
RX_LED_OFF;
|
||||
TX_LED_OFF;
|
||||
|
||||
PIOS_SYS_Reset();
|
||||
|
||||
while (1);
|
||||
*/
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
// *****************************************************************************
|
||||
|
||||
void ph_setFastPing(bool fast)
|
||||
{
|
||||
fast_ping = fast;
|
||||
}
|
||||
|
||||
// *****************************************************************************
|
||||
|
||||
uint8_t ph_getCurrentLinkState(const int connection_index)
|
||||
{
|
||||
if (connection_index < 0 || connection_index >= PH_MAX_CONNECTIONS)
|
||||
return 0;
|
||||
|
||||
return connection[connection_index].link_state;
|
||||
}
|
||||
|
||||
// *****************************************************************************
|
||||
|
||||
uint16_t ph_getRetries(const int connection_index)
|
||||
{
|
||||
if (connection_index < 0 || connection_index >= PH_MAX_CONNECTIONS)
|
||||
return 0;
|
||||
|
||||
return connection[connection_index].tx_retry_counter;
|
||||
}
|
||||
|
||||
// *****************************************************************************
|
||||
|
||||
int16_t ph_getLastRSSI(const int connection_index)
|
||||
{
|
||||
if (connection_index < 0 || connection_index >= PH_MAX_CONNECTIONS)
|
||||
return 0;
|
||||
|
||||
return connection[connection_index].rx_rssi_dBm;
|
||||
}
|
||||
|
||||
int32_t ph_getLastAFC(const int connection_index)
|
||||
{
|
||||
if (connection_index < 0 || connection_index >= PH_MAX_CONNECTIONS)
|
||||
return 0;
|
||||
|
||||
return connection[connection_index].rx_afc_Hz;
|
||||
}
|
||||
|
||||
// *****************************************************************************
|
||||
// set/get the carrier frequency
|
||||
|
||||
void ph_setNominalCarrierFrequency(uint32_t frequency_hz)
|
||||
{
|
||||
rfm22_setNominalCarrierFrequency(frequency_hz);
|
||||
}
|
||||
|
||||
uint32_t ph_getNominalCarrierFrequency(void)
|
||||
{
|
||||
return rfm22_getNominalCarrierFrequency();
|
||||
}
|
||||
|
||||
// *****************************************************************************
|
||||
// set/get the RF datarate
|
||||
|
||||
void ph_setDatarate(uint32_t datarate_bps)
|
||||
{
|
||||
rfm22_setDatarate(datarate_bps, TRUE);
|
||||
|
||||
uint32_t ms = 1280000ul / rfm22_getDatarate();
|
||||
if (ms < 10) ms = 10;
|
||||
else
|
||||
if (ms > 32000) ms = 32000;
|
||||
|
||||
for (int i = 0; i < PH_MAX_CONNECTIONS; i++)
|
||||
connection[i].tx_retry_time_slot_len = ms;
|
||||
}
|
||||
|
||||
uint32_t ph_getDatarate(void)
|
||||
{
|
||||
return rfm22_getDatarate();
|
||||
}
|
||||
|
||||
// *****************************************************************************
|
||||
|
||||
void ph_setTxPower(uint8_t tx_power)
|
||||
{
|
||||
rfm22_setTxPower(tx_power);
|
||||
}
|
||||
|
||||
uint8_t ph_getTxPower(void)
|
||||
{
|
||||
return rfm22_getTxPower();
|
||||
}
|
||||
|
||||
// *****************************************************************************
|
||||
// set the AES encryption key
|
||||
|
||||
void ph_set_AES128_key(const void *key)
|
||||
{
|
||||
if (!key)
|
||||
return;
|
||||
|
||||
memmove(aes_key, key, sizeof(aes_key));
|
||||
|
||||
// create the AES decryption key
|
||||
aes_decrypt_key_128_create(aes_key, (void *)&dec_aes_key);
|
||||
}
|
||||
|
||||
// *****************************************************************************
|
||||
|
||||
int ph_set_remote_serial_number(int connection_index, uint32_t sn)
|
||||
{
|
||||
random32 = updateCRC32(random32, 0xff);
|
||||
|
||||
if (ph_startConnect(connection_index, sn) >= 0)
|
||||
{
|
||||
t_connection *conn = &connection[connection_index];
|
||||
|
||||
// wipe any user data present in the buffers
|
||||
fifoBuf_init(&conn->tx_fifo_buffer, conn->tx_buffer, PH_FIFO_BUFFER_SIZE);
|
||||
fifoBuf_init(&conn->rx_fifo_buffer, conn->rx_buffer, PH_FIFO_BUFFER_SIZE);
|
||||
|
||||
return connection_index;
|
||||
}
|
||||
|
||||
return -4;
|
||||
}
|
||||
|
||||
void ph_set_remote_encryption(int connection_index, bool enabled, const void *key)
|
||||
{
|
||||
if (connection_index < 0 || connection_index >= PH_MAX_CONNECTIONS)
|
||||
return;
|
||||
|
||||
ph_set_AES128_key(key);
|
||||
|
||||
connection[connection_index].send_encrypted = enabled;
|
||||
}
|
||||
|
||||
// *****************************************************************************
|
||||
// can be called from an interrupt if you wish.
|
||||
// call this once every ms
|
||||
|
||||
void ph_1ms_tick(void)
|
||||
{
|
||||
if (booting) return;
|
||||
|
||||
if (saved_settings.mode == MODE_NORMAL)
|
||||
{
|
||||
// help randomize the encryptor cbc bytes
|
||||
register uint32_t *cbc = (uint32_t *)&enc_cbc;
|
||||
for (int i = 0; i < sizeof(enc_cbc) / 4; i++)
|
||||
{
|
||||
random32 = updateCRC32(random32, 0xff);
|
||||
*cbc++ ^= random32;
|
||||
}
|
||||
|
||||
for (int i = 0; i < PH_MAX_CONNECTIONS; i++)
|
||||
{
|
||||
t_connection *conn = &connection[i];
|
||||
|
||||
if (conn->tx_packet_timer < 0xffff)
|
||||
conn->tx_packet_timer++;
|
||||
|
||||
if (conn->link_state == LINK_CONNECTED)
|
||||
{ // we are connected
|
||||
|
||||
if (conn->ready_to_send_timer >= 0 && conn->ready_to_send_timer < 0x7fff)
|
||||
conn->ready_to_send_timer++;
|
||||
|
||||
if (conn->not_ready_timer >= 0 && conn->not_ready_timer < 0x7fffffff)
|
||||
conn->not_ready_timer++;
|
||||
|
||||
if (conn->data_speed_timer < 0xffff)
|
||||
{
|
||||
if (++conn->data_speed_timer >= 1000)
|
||||
{ // 1 second gone by
|
||||
conn->data_speed_timer = 0;
|
||||
conn->tx_data_speed = (conn->tx_data_speed + conn->tx_data_speed_count) >> 1;
|
||||
conn->tx_data_speed_count = 0;
|
||||
conn->rx_data_speed = (conn->rx_data_speed + conn->rx_data_speed_count) >> 1;
|
||||
conn->rx_data_speed_count = 0;
|
||||
}
|
||||
}
|
||||
}
|
||||
else
|
||||
{ // we are not connected
|
||||
if (conn->data_speed_timer) conn->data_speed_timer = 0;
|
||||
if (conn->tx_data_speed_count) conn->tx_data_speed_count = 0;
|
||||
if (conn->tx_data_speed) conn->tx_data_speed = 0;
|
||||
if (conn->rx_data_speed_count) conn->rx_data_speed_count = 0;
|
||||
if (conn->rx_data_speed) conn->rx_data_speed = 0;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// *****************************************************************************
|
||||
// call this as often as possible - not from an interrupt
|
||||
|
||||
void ph_process(void)
|
||||
{
|
||||
if (booting) return;
|
||||
|
||||
if (saved_settings.mode == MODE_NORMAL)
|
||||
{
|
||||
ph_processRxPacket();
|
||||
|
||||
for (int i = 0; i < PH_MAX_CONNECTIONS; i++)
|
||||
ph_processLinks(i);
|
||||
}
|
||||
else
|
||||
{
|
||||
|
||||
}
|
||||
}
|
||||
|
||||
// *****************************************************************************
|
||||
|
||||
void ph_disconnectAll(void)
|
||||
{
|
||||
for (int i = 0; i < PH_MAX_CONNECTIONS; i++)
|
||||
{
|
||||
random32 = updateCRC32(random32, 0xff);
|
||||
|
||||
t_connection *conn = &connection[i];
|
||||
|
||||
conn->serial_number = 0;
|
||||
|
||||
conn->tx_sequence = 0;
|
||||
conn->tx_sequence_data_size = 0;
|
||||
|
||||
conn->rx_sequence = 0;
|
||||
|
||||
fifoBuf_init(&conn->tx_fifo_buffer, conn->tx_buffer, PH_FIFO_BUFFER_SIZE);
|
||||
fifoBuf_init(&conn->rx_fifo_buffer, conn->rx_buffer, PH_FIFO_BUFFER_SIZE);
|
||||
|
||||
conn->link_state = LINK_DISCONNECTED;
|
||||
|
||||
conn->tx_packet_timer = 0;
|
||||
|
||||
conn->tx_retry_time_slots = 5;
|
||||
conn->tx_retry_time_slot_len = 40;
|
||||
conn->tx_retry_time = conn->tx_retry_time_slot_len * 4 + (random32 % conn->tx_retry_time_slots) * conn->tx_retry_time_slot_len * 4;
|
||||
conn->tx_retry_counter = 0;
|
||||
|
||||
conn->data_speed_timer = 0;
|
||||
conn->tx_data_speed_count = 0;
|
||||
conn->tx_data_speed = 0;
|
||||
conn->rx_data_speed_count = 0;
|
||||
conn->rx_data_speed = 0;
|
||||
|
||||
conn->ping_time = 8000 + (random32 % 100) * 10;
|
||||
conn->fast_ping_time = 600 + (random32 % 50) * 10;
|
||||
conn->pinging = false;
|
||||
|
||||
conn->rx_not_ready_mode = false;
|
||||
|
||||
conn->ready_to_send_timer = -1;
|
||||
|
||||
conn->not_ready_timer = -1;
|
||||
|
||||
conn->send_encrypted = false;
|
||||
|
||||
conn->rx_rssi_dBm = -200;
|
||||
conn->rx_afc_Hz = 0;
|
||||
}
|
||||
}
|
||||
|
||||
// *****************************************************************************
|
||||
|
||||
void ph_deinit(void)
|
||||
{
|
||||
ph_disconnectAll();
|
||||
}
|
||||
|
||||
void ph_init(uint32_t our_sn)
|
||||
{
|
||||
our_serial_number = our_sn; // remember our own serial number
|
||||
|
||||
fast_ping = false;
|
||||
|
||||
ph_disconnectAll();
|
||||
|
||||
// set the AES encryption key using the default AES key
|
||||
ph_set_AES128_key(default_aes_key);
|
||||
|
||||
// try too randomise the tx AES CBC bytes
|
||||
for (uint32_t j = 0, k = 0; j < 123 + (random32 & 1023); j++)
|
||||
{
|
||||
random32 = updateCRC32(random32, 0xff);
|
||||
enc_cbc[k] ^= random32 >> 3;
|
||||
if (++k >= sizeof(enc_cbc)) k = 0;
|
||||
}
|
||||
|
||||
// ******
|
||||
|
||||
rfm22_init_normal(saved_settings.min_frequency_Hz, saved_settings.max_frequency_Hz, rfm22_freqHopSize());
|
||||
|
||||
rfm22_TxDataByte_SetCallback(ph_TxDataByteCallback);
|
||||
rfm22_RxData_SetCallback(ph_RxDataCallback);
|
||||
|
||||
rfm22_setFreqCalibration(saved_settings.rf_xtal_cap);
|
||||
ph_setNominalCarrierFrequency(saved_settings.frequency_Hz);
|
||||
ph_setDatarate(saved_settings.max_rf_bandwidth);
|
||||
ph_setTxPower(saved_settings.max_tx_power);
|
||||
|
||||
ph_set_remote_encryption(0, saved_settings.aes_enable, (const void *)saved_settings.aes_key);
|
||||
ph_set_remote_serial_number(0, saved_settings.destination_id);
|
||||
|
||||
// ******
|
||||
}
|
||||
|
||||
// *****************************************************************************
|
@ -1,112 +0,0 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file pios_board.c
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @brief Defines board specific static initializers for hardware for the PipBee board.
|
||||
* @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
|
||||
*/
|
||||
|
||||
/* Pull in the board-specific static HW definitions.
|
||||
* Including .c files is a bit ugly but this allows all of
|
||||
* the HW definitions to be const and static to limit their
|
||||
* scope.
|
||||
*
|
||||
* NOTE: THIS IS THE ONLY PLACE THAT SHOULD EVER INCLUDE THIS FILE
|
||||
*/
|
||||
#include "board_hw_defs.c"
|
||||
|
||||
#include <pios.h>
|
||||
|
||||
#define PIOS_COM_TELEM_USB_RX_BUF_LEN 192
|
||||
#define PIOS_COM_TELEM_USB_TX_BUF_LEN 192
|
||||
|
||||
static uint8_t pios_com_telem_usb_rx_buffer[PIOS_COM_TELEM_USB_RX_BUF_LEN];
|
||||
static uint8_t pios_com_telem_usb_tx_buffer[PIOS_COM_TELEM_USB_TX_BUF_LEN];
|
||||
|
||||
#define PIOS_COM_SERIAL_RX_BUF_LEN 192
|
||||
#define PIOS_COM_SERIAL_TX_BUF_LEN 192
|
||||
|
||||
static uint8_t pios_com_serial_rx_buffer[PIOS_COM_SERIAL_RX_BUF_LEN];
|
||||
static uint8_t pios_com_serial_tx_buffer[PIOS_COM_SERIAL_TX_BUF_LEN];
|
||||
|
||||
uint32_t pios_com_serial_id;
|
||||
uint32_t pios_com_telem_usb_id;
|
||||
|
||||
/**
|
||||
* PIOS_Board_Init()
|
||||
* initializes all the core subsystems on this specific hardware
|
||||
* called from System/openpilot.c
|
||||
*/
|
||||
void PIOS_Board_Init(void) {
|
||||
// Bring up System using CMSIS functions, enables the LEDs.
|
||||
PIOS_SYS_Init();
|
||||
|
||||
// turn all the leds on
|
||||
USB_LED_ON;
|
||||
LINK_LED_ON;
|
||||
RX_LED_ON;
|
||||
TX_LED_ON;
|
||||
|
||||
// Delay system
|
||||
PIOS_DELAY_Init();
|
||||
|
||||
uint32_t pios_usart_serial_id;
|
||||
if (PIOS_USART_Init(&pios_usart_serial_id, &pios_usart_serial_cfg)) {
|
||||
PIOS_DEBUG_Assert(0);
|
||||
}
|
||||
if (PIOS_COM_Init(&pios_com_serial_id, &pios_usart_com_driver, pios_usart_serial_id,
|
||||
pios_com_serial_rx_buffer, sizeof(pios_com_serial_rx_buffer),
|
||||
pios_com_serial_tx_buffer, sizeof(pios_com_serial_tx_buffer))) {
|
||||
PIOS_DEBUG_Assert(0);
|
||||
}
|
||||
|
||||
#if defined(PIOS_INCLUDE_USB)
|
||||
/* Initialize board specific USB data */
|
||||
PIOS_USB_BOARD_DATA_Init();
|
||||
|
||||
if (PIOS_USB_DESC_HID_ONLY_Init()) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
|
||||
uint32_t pios_usb_id;
|
||||
PIOS_USB_Init(&pios_usb_id, &pios_usb_main_cfg);
|
||||
|
||||
#if defined(PIOS_INCLUDE_USB_HID) && defined(PIOS_INCLUDE_COM)
|
||||
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);
|
||||
}
|
||||
if (PIOS_COM_Init(&pios_com_telem_usb_id, &pios_usb_hid_com_driver, pios_usb_hid_id,
|
||||
pios_com_telem_usb_rx_buffer, sizeof(pios_com_telem_usb_rx_buffer),
|
||||
pios_com_telem_usb_tx_buffer, sizeof(pios_com_telem_usb_tx_buffer))) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_USB_HID && PIOS_INCLUDE_COM */
|
||||
|
||||
#endif /* PIOS_INCLUDE_USB_HID */
|
||||
|
||||
// ADC system
|
||||
// PIOS_ADC_Init();
|
||||
|
||||
// SPI link to master
|
||||
if (PIOS_SPI_Init(&pios_spi_port_id, &pios_spi_port_cfg)) {
|
||||
PIOS_DEBUG_Assert(0);
|
||||
}
|
||||
}
|
@ -1,631 +0,0 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file ppm.c
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @brief Sends or Receives the ppm values to/from the remote unit
|
||||
* @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 <string.h> // memmove
|
||||
|
||||
#include "main.h"
|
||||
#include "rfm22b.h"
|
||||
#include "saved_settings.h"
|
||||
#include "ppm.h"
|
||||
|
||||
#if defined(PIOS_COM_DEBUG)
|
||||
#define PPM_DEBUG
|
||||
#endif
|
||||
|
||||
// *************************************************************
|
||||
|
||||
#define PPM_OUT_FRAME_PERIOD_US 20000 // microseconds
|
||||
#define PPM_OUT_HIGH_PULSE_US 480 // microseconds
|
||||
#define PPM_OUT_MIN_CHANNEL_PULSE_US 850 // microseconds
|
||||
#define PPM_OUT_MAX_CHANNEL_PULSE_US 2200 // microseconds
|
||||
|
||||
#define PPM_IN_MIN_SYNC_PULSE_US 7000 // microseconds .. Pip's 6-chan TX goes down to 8.8ms
|
||||
#define PPM_IN_MIN_CHANNEL_PULSE_US 750 // microseconds
|
||||
#define PPM_IN_MAX_CHANNEL_PULSE_US 2400 // microseconds
|
||||
|
||||
// *************************************************************
|
||||
|
||||
uint8_t ppm_mode;
|
||||
|
||||
volatile bool ppm_initialising = true;
|
||||
|
||||
volatile uint32_t ppm_In_PrevFrames = 0;
|
||||
volatile uint32_t ppm_In_LastValidFrameTimer = 0;
|
||||
volatile uint32_t ppm_In_Frames = 0;
|
||||
volatile uint32_t ppm_In_ErrorFrames = 0;
|
||||
volatile uint8_t ppm_In_NoisyChannelCounter = 0;
|
||||
volatile int8_t ppm_In_ChannelsDetected = 0;
|
||||
volatile int8_t ppm_In_ChannelPulseIndex = -1;
|
||||
volatile int32_t ppm_In_PreviousValue = -1;
|
||||
volatile uint32_t ppm_In_PulseWidth = 0;
|
||||
volatile uint32_t ppm_In_ChannelPulseWidthNew[PIOS_PPM_MAX_CHANNELS];
|
||||
volatile uint32_t ppm_In_ChannelPulseWidth[PIOS_PPM_MAX_CHANNELS];
|
||||
|
||||
volatile uint16_t ppm_Out_ChannelPulseWidth[PIOS_PPM_MAX_CHANNELS];
|
||||
volatile uint32_t ppm_Out_SyncPulseWidth = PPM_OUT_FRAME_PERIOD_US;
|
||||
volatile int8_t ppm_Out_ChannelPulseIndex = -1;
|
||||
volatile uint8_t ppm_Out_ChannelsUsed = 0;
|
||||
|
||||
// *************************************************************
|
||||
|
||||
// Initialise the PPM INPUT
|
||||
void ppm_In_Init(void)
|
||||
{
|
||||
TIM_ICInitTypeDef TIM_ICInitStructure;
|
||||
|
||||
// disable the timer
|
||||
TIM_Cmd(PIOS_PPM_TIM, DISABLE);
|
||||
|
||||
ppm_In_PrevFrames = 0;
|
||||
ppm_In_NoisyChannelCounter = 0;
|
||||
ppm_In_LastValidFrameTimer = 0;
|
||||
ppm_In_Frames = 0;
|
||||
ppm_In_ErrorFrames = 0;
|
||||
ppm_In_ChannelsDetected = 0;
|
||||
ppm_In_ChannelPulseIndex = -1;
|
||||
ppm_In_PreviousValue = -1;
|
||||
ppm_In_PulseWidth = 0;
|
||||
|
||||
for (int i = 0; i < PIOS_PPM_MAX_CHANNELS; i++)
|
||||
{
|
||||
ppm_In_ChannelPulseWidthNew[i] = 0;
|
||||
ppm_In_ChannelPulseWidth[i] = 0;
|
||||
}
|
||||
|
||||
// Enable timer clock
|
||||
PIOS_PPM_TIMER_EN_RCC_FUNC;
|
||||
|
||||
// Enable timer interrupts
|
||||
NVIC_InitTypeDef NVIC_InitStructure;
|
||||
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID;
|
||||
NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0;
|
||||
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
|
||||
NVIC_InitStructure.NVIC_IRQChannel = PIOS_PPM_TIM_IRQ;
|
||||
NVIC_Init(&NVIC_InitStructure);
|
||||
|
||||
// Init PPM IN pin
|
||||
GPIO_InitTypeDef GPIO_InitStructure;
|
||||
GPIO_StructInit(&GPIO_InitStructure);
|
||||
GPIO_InitStructure.GPIO_Pin = PPM_IN_PIN;
|
||||
GPIO_InitStructure.GPIO_Mode = PPM_IN_MODE;
|
||||
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_2MHz;
|
||||
GPIO_Init(PPM_IN_PORT, &GPIO_InitStructure);
|
||||
|
||||
// remap the pin to switch it to timer mode
|
||||
if (PIOS_PPM_TIM == TIM2)
|
||||
{
|
||||
// GPIO_PinRemapConfig(GPIO_PartialRemap1_TIM2, ENABLE);
|
||||
GPIO_PinRemapConfig(GPIO_PartialRemap2_TIM2, ENABLE);
|
||||
// GPIO_PinRemapConfig(GPIO_FullRemap_TIM2, ENABLE);
|
||||
}
|
||||
|
||||
// Configure timer for input capture
|
||||
TIM_ICInitStructure.TIM_ICPolarity = TIM_ICPolarity_Rising;
|
||||
TIM_ICInitStructure.TIM_ICSelection = TIM_ICSelection_DirectTI;
|
||||
TIM_ICInitStructure.TIM_ICPrescaler = TIM_ICPSC_DIV1;
|
||||
TIM_ICInitStructure.TIM_ICFilter = 15; // 0 to 15
|
||||
TIM_ICInitStructure.TIM_Channel = PIOS_PPM_IN_TIM_CHANNEL;
|
||||
TIM_ICInit(PIOS_PPM_TIM_PORT, &TIM_ICInitStructure);
|
||||
|
||||
// Configure timer clocks
|
||||
TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure;
|
||||
TIM_TimeBaseStructInit(&TIM_TimeBaseStructure);
|
||||
TIM_TimeBaseStructure.TIM_Period = 25000 - 1; // 25ms - can be anything you like now really - up to 65536us
|
||||
TIM_TimeBaseStructure.TIM_Prescaler = (PIOS_MASTER_CLOCK / 1000000) - 1;
|
||||
TIM_TimeBaseStructure.TIM_ClockDivision = TIM_CKD_DIV1;
|
||||
TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up;
|
||||
TIM_InternalClockConfig(PIOS_PPM_TIM_PORT);
|
||||
TIM_TimeBaseInit(PIOS_PPM_TIM_PORT, &TIM_TimeBaseStructure);
|
||||
|
||||
// Enable the Capture Compare and Update Interrupts
|
||||
TIM_ITConfig(PIOS_PPM_TIM_PORT, PIOS_PPM_IN_TIM_CCR | TIM_IT_Update, ENABLE);
|
||||
|
||||
// Clear TIMER Capture compare and update interrupt pending bits
|
||||
TIM_ClearITPendingBit(PIOS_PPM_TIM_PORT, PIOS_PPM_IN_TIM_CCR | TIM_IT_Update);
|
||||
|
||||
// Enable timer
|
||||
TIM_Cmd(PIOS_PPM_TIM, ENABLE);
|
||||
|
||||
// Setup local variable which stays in this scope
|
||||
// Doing this here and using a local variable saves doing it in the ISR
|
||||
TIM_ICInitStructure.TIM_ICSelection = TIM_ICSelection_DirectTI;
|
||||
TIM_ICInitStructure.TIM_ICPrescaler = TIM_ICPSC_DIV1;
|
||||
TIM_ICInitStructure.TIM_ICFilter = 0x0;
|
||||
|
||||
#ifdef PPM_DEBUG
|
||||
DEBUG_PRINTF("ppm_in: initialised\r\n");
|
||||
#endif
|
||||
}
|
||||
|
||||
// TIMER capture/compare/update interrupt
|
||||
void PIOS_PPM_IN_CC_IRQ(void)
|
||||
{
|
||||
uint16_t new_value = 0;
|
||||
uint32_t period = (uint32_t)PIOS_PPM_TIM->ARR + 1;
|
||||
|
||||
if (booting || ppm_initialising)
|
||||
{ // clear the interrupts
|
||||
TIM_ClearITPendingBit(PIOS_PPM_TIM_PORT, PIOS_PPM_IN_TIM_CCR | TIM_IT_Update);
|
||||
return;
|
||||
}
|
||||
|
||||
// determine the interrupt source(s)
|
||||
bool update_int = TIM_GetITStatus(PIOS_PPM_TIM_PORT, TIM_IT_Update) == SET; // timer/counter overflow occured
|
||||
bool capture_int = TIM_GetITStatus(PIOS_PPM_TIM_PORT, PIOS_PPM_IN_TIM_CCR) == SET; // PPM input capture
|
||||
|
||||
if (capture_int)
|
||||
new_value = PIOS_PPM_IN_TIM_GETCAP_FUNC(PIOS_PPM_TIM_PORT);
|
||||
|
||||
// clear the interrupts
|
||||
TIM_ClearITPendingBit(PIOS_PPM_TIM_PORT, PIOS_PPM_IN_TIM_CCR | TIM_IT_Update);
|
||||
|
||||
// ********
|
||||
|
||||
uint32_t ticks = 0;
|
||||
if (update_int)
|
||||
{ // timer/counter overflowed
|
||||
|
||||
if (ppm_In_PreviousValue >= 0)
|
||||
ticks = (period - ppm_In_PreviousValue) + new_value;
|
||||
else
|
||||
{
|
||||
ticks = period;
|
||||
if (capture_int) ticks += new_value;
|
||||
}
|
||||
ppm_In_PreviousValue = -1;
|
||||
}
|
||||
else
|
||||
if (capture_int)
|
||||
{
|
||||
if (ppm_In_PreviousValue >= 0)
|
||||
ticks = new_value - ppm_In_PreviousValue;
|
||||
else
|
||||
ticks += new_value;
|
||||
}
|
||||
|
||||
ppm_In_PulseWidth += ticks;
|
||||
if (ppm_In_PulseWidth > 0x7fffffff)
|
||||
ppm_In_PulseWidth = 0x7fffffff; // prevent overflows
|
||||
|
||||
ppm_In_LastValidFrameTimer += ticks;
|
||||
if (ppm_In_LastValidFrameTimer > 0x7fffffff)
|
||||
ppm_In_LastValidFrameTimer = 0x7fffffff; // prevent overflows
|
||||
|
||||
if (capture_int)
|
||||
ppm_In_PreviousValue = new_value;
|
||||
|
||||
// ********
|
||||
|
||||
#ifdef PPM_DEBUG
|
||||
// DEBUG_PRINTF("ppm_in:");
|
||||
// if (update_int) DEBUG_PRINTF(" update");
|
||||
// if (capture_int) DEBUG_PRINTF(" capture");
|
||||
// DEBUG_PRINTF(" %u %u\r\n", ppm_In_LastValidFrameTimer, ppm_In_PulseWidth);
|
||||
#endif
|
||||
|
||||
if (ppm_In_LastValidFrameTimer >= 200000 && ppm_In_Frames > 0)
|
||||
{ // we haven't seen a valid PPM frame for at least 200ms
|
||||
for (int i = 0; i < PIOS_PPM_MAX_CHANNELS; i++)
|
||||
ppm_In_ChannelPulseWidth[i] = 0;
|
||||
ppm_In_Frames = 0;
|
||||
ppm_In_ErrorFrames = 0;
|
||||
}
|
||||
|
||||
if (ppm_In_ChannelPulseIndex < 0 || ppm_In_PulseWidth > PPM_IN_MAX_CHANNEL_PULSE_US)
|
||||
{ // we are looking for a SYNC pulse, or we are receiving one
|
||||
|
||||
if (ppm_In_ChannelPulseIndex >= 0)
|
||||
{ // it's either the start of a sync pulse or a noisy channel .. assume it's the end of a PPM frame
|
||||
|
||||
if (ppm_In_ChannelPulseIndex > 0)
|
||||
{
|
||||
if (ppm_In_Frames < 0xffffffff)
|
||||
ppm_In_Frames++; // update frame counter
|
||||
|
||||
#ifdef PPM_DEBUG
|
||||
// DEBUG_PRINTF("ppm_in: %u %u\r\n", ppm_In_ChannelsDetected, ppm_In_ChannelPulseIndex);
|
||||
#endif
|
||||
|
||||
if (ppm_In_ChannelsDetected > 0 &&
|
||||
ppm_In_ChannelsDetected == ppm_In_ChannelPulseIndex &&
|
||||
ppm_In_NoisyChannelCounter <= 2)
|
||||
{ // detected same number of channels as in previous PPM frame .. save the new channel PWM values
|
||||
#ifdef PPM_DEBUG
|
||||
// DEBUG_PRINTF("ppm_in: %u channels detected\r\n", ppm_In_ChannelPulseIndex);
|
||||
#endif
|
||||
|
||||
for (int i = 0; i < PIOS_PPM_MAX_CHANNELS; i++)
|
||||
ppm_In_ChannelPulseWidth[i] = ppm_In_ChannelPulseWidthNew[i];
|
||||
|
||||
ppm_In_LastValidFrameTimer = 0; // reset timer
|
||||
}
|
||||
else
|
||||
{
|
||||
if ((ppm_In_ChannelsDetected > 0 && ppm_In_ChannelsDetected != ppm_In_ChannelPulseIndex) ||
|
||||
ppm_In_NoisyChannelCounter >= 2)
|
||||
{
|
||||
if (ppm_In_ErrorFrames < 0xffffffff)
|
||||
ppm_In_ErrorFrames++;
|
||||
}
|
||||
}
|
||||
ppm_In_ChannelsDetected = ppm_In_ChannelPulseIndex; // the number of channels we found in this frame
|
||||
}
|
||||
|
||||
ppm_In_ChannelPulseIndex = -1; // back to looking for a SYNC pulse
|
||||
}
|
||||
|
||||
if (ppm_In_PulseWidth >= PPM_IN_MIN_SYNC_PULSE_US)
|
||||
{ // SYNC pulse found
|
||||
ppm_In_NoisyChannelCounter = 0; // reset noisy channel detector
|
||||
ppm_In_ChannelPulseIndex = 0; // start of PPM frame
|
||||
}
|
||||
}
|
||||
else
|
||||
if (capture_int)
|
||||
{ // CHANNEL pulse
|
||||
|
||||
if (ppm_In_PulseWidth < PPM_IN_MIN_CHANNEL_PULSE_US)
|
||||
{ // bad/noisy channel pulse .. reset state to wait for next SYNC pulse
|
||||
ppm_In_ChannelPulseIndex = -1;
|
||||
|
||||
if (ppm_In_ErrorFrames < 0xffffffff)
|
||||
ppm_In_ErrorFrames++;
|
||||
}
|
||||
else
|
||||
{ // pulse width is within the accepted tolerance range for a channel
|
||||
if (ppm_In_ChannelPulseIndex < PIOS_PPM_MAX_CHANNELS)
|
||||
{
|
||||
if (ppm_In_ChannelPulseWidthNew[ppm_In_ChannelPulseIndex] > 0)
|
||||
{
|
||||
int32_t difference = (int32_t)ppm_In_PulseWidth - ppm_In_ChannelPulseWidthNew[ppm_In_ChannelPulseIndex];
|
||||
if (abs(difference) >= 600)
|
||||
ppm_In_NoisyChannelCounter++; // possibly a noisy channel - or an RC switch was moved
|
||||
}
|
||||
|
||||
ppm_In_ChannelPulseWidthNew[ppm_In_ChannelPulseIndex] = ppm_In_PulseWidth; // save it
|
||||
}
|
||||
|
||||
if (ppm_In_ChannelPulseIndex < 127)
|
||||
ppm_In_ChannelPulseIndex++; // next channel
|
||||
}
|
||||
}
|
||||
|
||||
if (capture_int)
|
||||
ppm_In_PulseWidth = 0;
|
||||
|
||||
// ********
|
||||
}
|
||||
|
||||
uint32_t ppm_In_NewFrame(void)
|
||||
{
|
||||
if (booting || ppm_initialising)
|
||||
return 0;
|
||||
|
||||
if (ppm_In_Frames >= 2 && ppm_In_Frames != ppm_In_PrevFrames)
|
||||
{ // we have a new PPM frame
|
||||
ppm_In_PrevFrames = ppm_In_Frames;
|
||||
return ppm_In_PrevFrames;
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
int32_t ppm_In_GetChannelPulseWidth(uint8_t channel)
|
||||
{
|
||||
if (booting || ppm_initialising)
|
||||
return -1;
|
||||
|
||||
// Return error if channel not available
|
||||
if (channel >= PIOS_PPM_MAX_CHANNELS || channel >= ppm_In_ChannelsDetected)
|
||||
return -2;
|
||||
|
||||
return ppm_In_ChannelPulseWidth[channel]; // return channel pulse width
|
||||
}
|
||||
|
||||
// *************************************************************
|
||||
|
||||
// Initialise the PPM INPUT
|
||||
void ppm_Out_Init(void)
|
||||
{
|
||||
// disable the timer
|
||||
TIM_Cmd(PIOS_PPM_TIM, DISABLE);
|
||||
|
||||
ppm_Out_SyncPulseWidth = PPM_OUT_FRAME_PERIOD_US;
|
||||
ppm_Out_ChannelPulseIndex = -1;
|
||||
ppm_Out_ChannelsUsed = 0;
|
||||
for (int i = 0; i < PIOS_PPM_MAX_CHANNELS; i++)
|
||||
ppm_Out_ChannelPulseWidth[i] = 1000;
|
||||
// ppm_Out_ChannelPulseWidth[i] = 1000 + i * 100; // TEST ONLY
|
||||
|
||||
// ppm_Out_ChannelsUsed = 5; // TEST ONLY
|
||||
|
||||
// Enable timer clock
|
||||
PIOS_PPM_TIMER_EN_RCC_FUNC;
|
||||
|
||||
// Init PPM OUT pin
|
||||
GPIO_InitTypeDef GPIO_InitStructure;
|
||||
GPIO_StructInit(&GPIO_InitStructure);
|
||||
GPIO_InitStructure.GPIO_Pin = PPM_OUT_PIN;
|
||||
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP;
|
||||
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_10MHz;
|
||||
GPIO_Init(PPM_OUT_PORT, &GPIO_InitStructure);
|
||||
|
||||
// remap the pin to switch it to timer mode
|
||||
// GPIO_PinRemapConfig(GPIO_PartialRemap1_TIM2, ENABLE);
|
||||
// GPIO_PinRemapConfig(GPIO_PartialRemap2_TIM2, ENABLE);
|
||||
GPIO_PinRemapConfig(GPIO_FullRemap_TIM2, ENABLE);
|
||||
|
||||
// Enable timer interrupt
|
||||
NVIC_InitTypeDef NVIC_InitStructure;
|
||||
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID;
|
||||
NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0;
|
||||
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
|
||||
NVIC_InitStructure.NVIC_IRQChannel = PIOS_PPM_TIM_IRQ;
|
||||
NVIC_Init(&NVIC_InitStructure);
|
||||
|
||||
// Time base configuration
|
||||
TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure;
|
||||
TIM_TimeBaseStructInit(&TIM_TimeBaseStructure);
|
||||
TIM_TimeBaseStructure.TIM_Period = ppm_Out_SyncPulseWidth - 1;
|
||||
TIM_TimeBaseStructure.TIM_Prescaler = (PIOS_MASTER_CLOCK / 1000000) - 1;
|
||||
TIM_TimeBaseStructure.TIM_ClockDivision = TIM_CKD_DIV1;
|
||||
TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up;
|
||||
TIM_InternalClockConfig(PIOS_PPM_TIM_PORT);
|
||||
TIM_TimeBaseInit(PIOS_PPM_TIM_PORT, &TIM_TimeBaseStructure);
|
||||
|
||||
// Set up for output compare function
|
||||
TIM_OCInitTypeDef TIM_OCInitStructure;
|
||||
TIM_OCInitStructure.TIM_OCMode = TIM_OCMode_PWM1;
|
||||
TIM_OCInitStructure.TIM_OutputState = TIM_OutputState_Enable;
|
||||
TIM_OCInitStructure.TIM_OutputNState = TIM_OutputNState_Disable;
|
||||
TIM_OCInitStructure.TIM_Pulse = PPM_OUT_HIGH_PULSE_US;
|
||||
TIM_OCInitStructure.TIM_OCPolarity = TIM_OCPolarity_High;
|
||||
TIM_OCInitStructure.TIM_OCNPolarity = TIM_OCPolarity_High;
|
||||
TIM_OCInitStructure.TIM_OCIdleState = TIM_OCIdleState_Reset;
|
||||
TIM_OCInitStructure.TIM_OCNIdleState = TIM_OCNIdleState_Reset;
|
||||
TIM_OC3Init(PIOS_PPM_TIM, &TIM_OCInitStructure);
|
||||
TIM_OC3PreloadConfig(PIOS_PPM_TIM, TIM_OCPreload_Enable);
|
||||
|
||||
TIM_ARRPreloadConfig(PIOS_PPM_TIM, ENABLE);
|
||||
|
||||
// TIMER Main Output Enable
|
||||
TIM_CtrlPWMOutputs(PIOS_PPM_TIM, ENABLE);
|
||||
|
||||
// TIM IT enable
|
||||
TIM_ITConfig(PIOS_PPM_TIM, PIOS_PPM_OUT_TIM_CCR, ENABLE);
|
||||
|
||||
// Clear TIMER Capture compare interrupt pending bit
|
||||
TIM_ClearITPendingBit(PIOS_PPM_TIM_PORT, PIOS_PPM_IN_TIM_CCR);
|
||||
|
||||
// Enable timer
|
||||
TIM_Cmd(PIOS_PPM_TIM, ENABLE);
|
||||
|
||||
#ifdef PPM_DEBUG
|
||||
DEBUG_PRINTF("ppm_out: initialised\r\n");
|
||||
#endif
|
||||
}
|
||||
|
||||
// TIMER capture/compare interrupt
|
||||
void PIOS_PPM_OUT_CC_IRQ(void)
|
||||
{
|
||||
// clear the interrupt
|
||||
TIM_ClearITPendingBit(PIOS_PPM_TIM_PORT, PIOS_PPM_OUT_TIM_CCR);
|
||||
|
||||
if (booting || ppm_initialising)
|
||||
return;
|
||||
|
||||
// *************************
|
||||
// update the TIMER period (channel pulse width)
|
||||
|
||||
if (ppm_Out_ChannelPulseIndex < 0)
|
||||
{ // SYNC PULSE
|
||||
TIM_SetAutoreload(PIOS_PPM_TIM, ppm_Out_SyncPulseWidth - 1); // sync pulse length
|
||||
ppm_Out_SyncPulseWidth = PPM_OUT_FRAME_PERIOD_US; // reset sync period
|
||||
|
||||
if (ppm_Out_ChannelsUsed > 0)
|
||||
ppm_Out_ChannelPulseIndex = 0; // onto channel-1
|
||||
}
|
||||
else
|
||||
{ // CHANNEL PULSE
|
||||
uint16_t pulse_width = ppm_Out_ChannelPulseWidth[ppm_Out_ChannelPulseIndex];
|
||||
if (pulse_width < PPM_OUT_MIN_CHANNEL_PULSE_US) pulse_width = PPM_OUT_MIN_CHANNEL_PULSE_US;
|
||||
else
|
||||
if (pulse_width > PPM_OUT_MAX_CHANNEL_PULSE_US) pulse_width = PPM_OUT_MAX_CHANNEL_PULSE_US;
|
||||
|
||||
TIM_SetAutoreload(PIOS_PPM_TIM, pulse_width - 1); // channel pulse width
|
||||
ppm_Out_SyncPulseWidth -= pulse_width; // maintain constant PPM frame period
|
||||
|
||||
// TEST ONLY
|
||||
// pulse_width += 4;
|
||||
// if (pulse_width > 2000) pulse_width = 1000;
|
||||
// ppm_Out_ChannelPulseWidth[ppm_Out_ChannelPulseIndex] = pulse_width;
|
||||
|
||||
ppm_Out_ChannelPulseIndex++;
|
||||
if (ppm_Out_ChannelPulseIndex >= ppm_Out_ChannelsUsed || ppm_Out_ChannelPulseIndex >= PIOS_PPM_MAX_CHANNELS)
|
||||
ppm_Out_ChannelPulseIndex = -1; // back to SYNC pulse
|
||||
}
|
||||
|
||||
// *************************
|
||||
}
|
||||
|
||||
// *************************************************************
|
||||
// TIMER capture/compare interrupt
|
||||
|
||||
void PIOS_PPM_CC_IRQ_FUNC(void)
|
||||
{
|
||||
if (ppm_mode == MODE_PPM_TX)
|
||||
PIOS_PPM_IN_CC_IRQ();
|
||||
else
|
||||
if (ppm_mode == MODE_PPM_RX)
|
||||
PIOS_PPM_OUT_CC_IRQ();
|
||||
else
|
||||
TIM_ClearITPendingBit(PIOS_PPM_TIM_PORT, PIOS_PPM_IN_TIM_CCR | TIM_IT_Update); // clear the interrupts
|
||||
}
|
||||
|
||||
// *************************************************************
|
||||
// can be called from an interrupt if you wish
|
||||
// call this once every ms
|
||||
|
||||
void ppm_1ms_tick(void)
|
||||
{
|
||||
if (booting || ppm_initialising)
|
||||
return;
|
||||
|
||||
|
||||
}
|
||||
|
||||
// *************************************************************
|
||||
// return a byte for the tx packet transmission.
|
||||
//
|
||||
// return value < 0 if no more bytes available, otherwise return byte to be sent
|
||||
|
||||
int16_t ppm_TxDataByteCallback(void)
|
||||
{
|
||||
return -1;
|
||||
}
|
||||
|
||||
// *************************************************************
|
||||
// we are being given a block of received bytes
|
||||
//
|
||||
// return TRUE to continue current packet receive, otherwise return FALSE to halt current packet reception
|
||||
|
||||
bool ppm_RxDataCallback(void *data, uint8_t len)
|
||||
{
|
||||
return true;
|
||||
}
|
||||
|
||||
// *************************************************************
|
||||
// call this from the main loop (not interrupt) as often as possible
|
||||
|
||||
void ppm_process(void)
|
||||
{
|
||||
if (booting || ppm_initialising)
|
||||
return;
|
||||
|
||||
if (ppm_mode == MODE_PPM_TX)
|
||||
{
|
||||
if (ppm_In_NewFrame() > 0)
|
||||
{ // we have a new PPM frame to send
|
||||
|
||||
#ifdef PPM_DEBUG
|
||||
DEBUG_PRINTF("ppm_in: %5u %5u ..", ppm_In_Frames, ppm_In_ErrorFrames);
|
||||
#endif
|
||||
|
||||
for (int i = 0; i < PIOS_PPM_MAX_CHANNELS && i < ppm_In_ChannelsDetected; i++)
|
||||
{
|
||||
// int32_t pwm = ppm_In_GetChannelPulseWidth(i);
|
||||
|
||||
#ifdef PPM_DEBUG
|
||||
DEBUG_PRINTF(" %4u", ppm_In_GetChannelPulseWidth(i));
|
||||
#endif
|
||||
|
||||
// TODO:
|
||||
}
|
||||
|
||||
#ifdef PPM_DEBUG
|
||||
DEBUG_PRINTF("\r\n");
|
||||
#endif
|
||||
}
|
||||
}
|
||||
else
|
||||
if (ppm_mode == MODE_PPM_RX)
|
||||
{
|
||||
// TODO:
|
||||
}
|
||||
}
|
||||
|
||||
// *************************************************************
|
||||
|
||||
void ppm_deinit(void)
|
||||
{
|
||||
ppm_initialising = true;
|
||||
|
||||
ppm_mode = 0;
|
||||
|
||||
// disable timer
|
||||
TIM_Cmd(PIOS_PPM_TIM, DISABLE);
|
||||
|
||||
// Disable timer clock
|
||||
PIOS_PPM_TIMER_DIS_RCC_FUNC;
|
||||
|
||||
// TIM IT disable
|
||||
TIM_ITConfig(PIOS_PPM_TIM, PIOS_PPM_IN_TIM_CCR | PIOS_PPM_OUT_TIM_CCR, DISABLE);
|
||||
|
||||
// TIMER Main Output Disable
|
||||
TIM_CtrlPWMOutputs(PIOS_PPM_TIM, DISABLE);
|
||||
|
||||
// un-remap the PPM pins
|
||||
GPIO_PinRemapConfig(GPIO_FullRemap_TIM2, DISABLE);
|
||||
|
||||
// Disable timer interrupt
|
||||
NVIC_InitTypeDef NVIC_InitStructure;
|
||||
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID;
|
||||
NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0;
|
||||
NVIC_InitStructure.NVIC_IRQChannelCmd = DISABLE;
|
||||
NVIC_InitStructure.NVIC_IRQChannel = PIOS_PPM_TIM_IRQ;
|
||||
NVIC_Init(&NVIC_InitStructure);
|
||||
|
||||
ppm_initialising = false;
|
||||
}
|
||||
|
||||
void ppm_init(uint32_t our_sn)
|
||||
{
|
||||
ppm_deinit();
|
||||
|
||||
ppm_initialising = true;
|
||||
|
||||
ppm_mode = saved_settings.mode;
|
||||
|
||||
#if defined(PPM_DEBUG)
|
||||
DEBUG_PRINTF("\r\nPPM init\r\n");
|
||||
#endif
|
||||
|
||||
if (ppm_mode == MODE_PPM_TX)
|
||||
{
|
||||
ppm_In_Init();
|
||||
rfm22_init_tx_stream(saved_settings.min_frequency_Hz, saved_settings.max_frequency_Hz);
|
||||
}
|
||||
else
|
||||
if (ppm_mode == MODE_PPM_RX)
|
||||
{
|
||||
ppm_Out_Init();
|
||||
rfm22_init_rx_stream(saved_settings.min_frequency_Hz, saved_settings.max_frequency_Hz);
|
||||
}
|
||||
|
||||
rfm22_TxDataByte_SetCallback(ppm_TxDataByteCallback);
|
||||
rfm22_RxData_SetCallback(ppm_RxDataCallback);
|
||||
|
||||
rfm22_setFreqCalibration(saved_settings.rf_xtal_cap);
|
||||
rfm22_setNominalCarrierFrequency(saved_settings.frequency_Hz);
|
||||
rfm22_setDatarate(saved_settings.max_rf_bandwidth, FALSE);
|
||||
rfm22_setTxPower(saved_settings.max_tx_power);
|
||||
|
||||
if (ppm_mode == MODE_PPM_TX)
|
||||
rfm22_setTxStream();
|
||||
|
||||
ppm_initialising = false;
|
||||
}
|
||||
|
||||
// *************************************************************
|
@ -1,500 +0,0 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file api_comms.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @brief RF Module hardware layer
|
||||
* @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
|
||||
*/
|
||||
|
||||
|
||||
|
||||
|
||||
// see http://newwiki.openpilot.org/display/Doc/UAVTalk .. for UAVTalk protocol description
|
||||
//
|
||||
// This module scans for OP UAVTalk packets in the comm-port or RF data streams.
|
||||
// It will discard any corrupt/invalid packets and only pass valid ones.
|
||||
|
||||
|
||||
|
||||
#include <string.h>
|
||||
|
||||
#include "stm32f10x.h"
|
||||
#include "gpio_in.h"
|
||||
#include "api_comms.h"
|
||||
#include "packet_handler.h"
|
||||
#include "main.h"
|
||||
|
||||
#if defined(PIOS_COM_DEBUG)
|
||||
#define API_DEBUG
|
||||
#endif
|
||||
|
||||
// *****************************************************************************
|
||||
// modem configuration packets
|
||||
|
||||
typedef struct
|
||||
{
|
||||
uint32_t marker;
|
||||
uint32_t serial_number;
|
||||
uint8_t type;
|
||||
uint8_t spare;
|
||||
uint16_t data_size;
|
||||
uint32_t header_crc;
|
||||
uint32_t data_crc;
|
||||
// uint8_t data[0];
|
||||
} __attribute__((__packed__)) t_pipx_config_header;
|
||||
|
||||
typedef struct
|
||||
{
|
||||
uint8_t mode;
|
||||
uint8_t state;
|
||||
} __attribute__((__packed__)) t_pipx_config_data_mode_state;
|
||||
|
||||
typedef struct
|
||||
{
|
||||
uint32_t serial_baudrate; // serial uart baudrate
|
||||
|
||||
uint32_t destination_id;
|
||||
|
||||
uint32_t min_frequency_Hz;
|
||||
uint32_t max_frequency_Hz;
|
||||
uint32_t frequency_Hz;
|
||||
|
||||
uint32_t max_rf_bandwidth;
|
||||
|
||||
uint8_t max_tx_power;
|
||||
|
||||
uint8_t frequency_band;
|
||||
|
||||
uint8_t rf_xtal_cap;
|
||||
|
||||
bool aes_enable;
|
||||
uint8_t aes_key[16];
|
||||
|
||||
uint16_t frequency_step_size;
|
||||
} __attribute__((__packed__)) t_pipx_config_data_settings;
|
||||
|
||||
typedef struct
|
||||
{
|
||||
uint32_t start_frequency;
|
||||
uint16_t frequency_step_size;
|
||||
uint16_t magnitudes;
|
||||
// int8_t magnitude[0];
|
||||
} __attribute__((__packed__)) t_pipx_config_data_spectrum;
|
||||
|
||||
// *****************************************************************************
|
||||
|
||||
typedef struct
|
||||
{
|
||||
uint8_t sync_byte;
|
||||
uint8_t message_type;
|
||||
uint16_t packet_size; // not including CRC byte
|
||||
uint32_t object_id;
|
||||
} __attribute__((__packed__)) t_uav_header1;
|
||||
|
||||
typedef struct
|
||||
{
|
||||
uint8_t sync_byte;
|
||||
uint8_t message_type;
|
||||
uint16_t packet_size; // not including CRC byte
|
||||
uint32_t object_id;
|
||||
uint16_t instance_id;
|
||||
} __attribute__((__packed__)) t_uav_header2;
|
||||
|
||||
#define SYNC_VAL 0x3C
|
||||
#define TYPE_MASK 0xFC
|
||||
#define TYPE_VER 0x20
|
||||
#define TYPE_OBJ (TYPE_VER | 0x00)
|
||||
#define TYPE_OBJ_REQ (TYPE_VER | 0x01)
|
||||
#define TYPE_OBJ_ACK (TYPE_VER | 0x02)
|
||||
#define TYPE_ACK (TYPE_VER | 0x03)
|
||||
|
||||
#define MIN_HEADER_LENGTH sizeof(t_uav_header1)
|
||||
#define MAX_HEADER_LENGTH sizeof(t_uav_header2)
|
||||
#define MAX_PAYLOAD_LENGTH 256
|
||||
#define CHECKSUM_LENGTH 1
|
||||
|
||||
#define MAX_PACKET_LENGTH (MAX_HEADER_LENGTH + MAX_PAYLOAD_LENGTH + CHECKSUM_LENGTH)
|
||||
|
||||
// CRC lookup table
|
||||
static const uint8_t crc_table[256] = {
|
||||
0x00, 0x07, 0x0e, 0x09, 0x1c, 0x1b, 0x12, 0x15, 0x38, 0x3f, 0x36, 0x31, 0x24, 0x23, 0x2a, 0x2d,
|
||||
0x70, 0x77, 0x7e, 0x79, 0x6c, 0x6b, 0x62, 0x65, 0x48, 0x4f, 0x46, 0x41, 0x54, 0x53, 0x5a, 0x5d,
|
||||
0xe0, 0xe7, 0xee, 0xe9, 0xfc, 0xfb, 0xf2, 0xf5, 0xd8, 0xdf, 0xd6, 0xd1, 0xc4, 0xc3, 0xca, 0xcd,
|
||||
0x90, 0x97, 0x9e, 0x99, 0x8c, 0x8b, 0x82, 0x85, 0xa8, 0xaf, 0xa6, 0xa1, 0xb4, 0xb3, 0xba, 0xbd,
|
||||
0xc7, 0xc0, 0xc9, 0xce, 0xdb, 0xdc, 0xd5, 0xd2, 0xff, 0xf8, 0xf1, 0xf6, 0xe3, 0xe4, 0xed, 0xea,
|
||||
0xb7, 0xb0, 0xb9, 0xbe, 0xab, 0xac, 0xa5, 0xa2, 0x8f, 0x88, 0x81, 0x86, 0x93, 0x94, 0x9d, 0x9a,
|
||||
0x27, 0x20, 0x29, 0x2e, 0x3b, 0x3c, 0x35, 0x32, 0x1f, 0x18, 0x11, 0x16, 0x03, 0x04, 0x0d, 0x0a,
|
||||
0x57, 0x50, 0x59, 0x5e, 0x4b, 0x4c, 0x45, 0x42, 0x6f, 0x68, 0x61, 0x66, 0x73, 0x74, 0x7d, 0x7a,
|
||||
0x89, 0x8e, 0x87, 0x80, 0x95, 0x92, 0x9b, 0x9c, 0xb1, 0xb6, 0xbf, 0xb8, 0xad, 0xaa, 0xa3, 0xa4,
|
||||
0xf9, 0xfe, 0xf7, 0xf0, 0xe5, 0xe2, 0xeb, 0xec, 0xc1, 0xc6, 0xcf, 0xc8, 0xdd, 0xda, 0xd3, 0xd4,
|
||||
0x69, 0x6e, 0x67, 0x60, 0x75, 0x72, 0x7b, 0x7c, 0x51, 0x56, 0x5f, 0x58, 0x4d, 0x4a, 0x43, 0x44,
|
||||
0x19, 0x1e, 0x17, 0x10, 0x05, 0x02, 0x0b, 0x0c, 0x21, 0x26, 0x2f, 0x28, 0x3d, 0x3a, 0x33, 0x34,
|
||||
0x4e, 0x49, 0x40, 0x47, 0x52, 0x55, 0x5c, 0x5b, 0x76, 0x71, 0x78, 0x7f, 0x6a, 0x6d, 0x64, 0x63,
|
||||
0x3e, 0x39, 0x30, 0x37, 0x22, 0x25, 0x2c, 0x2b, 0x06, 0x01, 0x08, 0x0f, 0x1a, 0x1d, 0x14, 0x13,
|
||||
0xae, 0xa9, 0xa0, 0xa7, 0xb2, 0xb5, 0xbc, 0xbb, 0x96, 0x91, 0x98, 0x9f, 0x8a, 0x8d, 0x84, 0x83,
|
||||
0xde, 0xd9, 0xd0, 0xd7, 0xc2, 0xc5, 0xcc, 0xcb, 0xe6, 0xe1, 0xe8, 0xef, 0xfa, 0xfd, 0xf4, 0xf3
|
||||
};
|
||||
|
||||
// *****************************************************************************
|
||||
// local variables
|
||||
|
||||
uint32_t api_previous_com_port = 0;
|
||||
|
||||
volatile uint16_t api_rx_timer = 0;
|
||||
volatile uint16_t api_tx_timer = 0;
|
||||
|
||||
uint8_t api_rx_buffer[MAX_PACKET_LENGTH] __attribute__ ((aligned(4)));
|
||||
uint16_t api_rx_buffer_wr;
|
||||
|
||||
uint8_t api_tx_buffer[MAX_PACKET_LENGTH] __attribute__ ((aligned(4)));
|
||||
uint16_t api_tx_buffer_wr;
|
||||
|
||||
// *****************************************************************************
|
||||
// 8-bit CRC updating
|
||||
|
||||
uint8_t api_updateCRC_byte(uint8_t crc, uint8_t b)
|
||||
{
|
||||
return crc_table[crc ^ b];
|
||||
}
|
||||
|
||||
uint8_t api_updateCRC_buffer(uint8_t crc, const void *data, int32_t length)
|
||||
{
|
||||
// use registers for speed
|
||||
register uint8_t crc8 = crc;
|
||||
register const uint8_t *p = (uint8_t *)data;
|
||||
|
||||
for (register int32_t i = length; i > 0; i--)
|
||||
crc8 = crc_table[crc8 ^ *p++];
|
||||
|
||||
return crc8;
|
||||
}
|
||||
|
||||
// returned value < 0 if no valid packet detected.
|
||||
// otherwise returned value is the total size of the valid UAVTalk packet found in the buffer.
|
||||
//
|
||||
// any corrupt/invalid UAVTalk packets/data are deleted from the buffer and we scan for the next valid packet.
|
||||
int16_t api_scanForUAVTalkPacket(void *buf, uint16_t *len)
|
||||
{
|
||||
uint8_t *buffer = (uint8_t *)buf;
|
||||
|
||||
t_uav_header1 *header1 = (t_uav_header1 *)buf;
|
||||
// t_uav_header2 *header2 = (t_uav_header2 *)buf;
|
||||
|
||||
register uint16_t num_bytes = *len;
|
||||
|
||||
if (num_bytes < MIN_HEADER_LENGTH + CHECKSUM_LENGTH)
|
||||
return -1; // not yet enough bytes for a complete packet
|
||||
|
||||
while (TRUE)
|
||||
{
|
||||
// scan the buffer for the start of a UAVTalk packet
|
||||
for (uint16_t i = 0; i < num_bytes; i++)
|
||||
{
|
||||
if (api_rx_buffer[i] != SYNC_VAL)
|
||||
continue; // not the start of a packet - move on to the next byte in the buffer
|
||||
|
||||
// possible start of packet found - we found a SYNC byte
|
||||
|
||||
if (i > 0)
|
||||
{ // remove/delete leading bytes before the SYNC byte
|
||||
num_bytes -= i;
|
||||
if (num_bytes > 0)
|
||||
memmove(buffer, buffer + i, num_bytes);
|
||||
*len = num_bytes;
|
||||
}
|
||||
break;
|
||||
}
|
||||
|
||||
if (num_bytes < MIN_HEADER_LENGTH + CHECKSUM_LENGTH)
|
||||
return -2; // not yet enough bytes for a complete packet
|
||||
|
||||
if (header1->sync_byte != SYNC_VAL)
|
||||
{ // SYNC byte was not found - start of UAVTalk packet not found in any of the data in the buffer
|
||||
*len = 0; // empty the entire buffer
|
||||
return -3;
|
||||
}
|
||||
|
||||
if (header1->packet_size < MIN_HEADER_LENGTH || header1->packet_size > MAX_HEADER_LENGTH + MAX_PAYLOAD_LENGTH)
|
||||
{ // the packet size value is too small or too big - assume either a corrupt UAVTalk packet or we are at the start of a packet
|
||||
// if (--num_bytes > 0)
|
||||
// memmove(buffer, buffer + 1, num_bytes); // remove 1st byte
|
||||
// *len = num_bytes;
|
||||
buffer[0] ^= 0xaa; // corrupt the sync byte - we'll move the buffer bytes down further up in the code
|
||||
continue; // continue scanning for a valid packet in the buffer
|
||||
}
|
||||
|
||||
if (num_bytes < header1->packet_size + CHECKSUM_LENGTH)
|
||||
{ // not yet enough bytes for a complete packet
|
||||
return -4;
|
||||
}
|
||||
|
||||
// check the packet CRC
|
||||
uint8_t crc1 = api_updateCRC_buffer(0, buffer, header1->packet_size);
|
||||
uint8_t crc2 = buffer[header1->packet_size];
|
||||
if (crc1 != crc2)
|
||||
{ // faulty CRC
|
||||
// if (--num_bytes > 0)
|
||||
// memmove(buffer, buffer + 1, num_bytes); // remove 1st byte
|
||||
// *len = num_bytes;
|
||||
buffer[0] ^= 0xaa; // corrupt the sync byte - we'll move the buffer bytes down further up in the code
|
||||
|
||||
#if defined(API_DEBUG)
|
||||
DEBUG_PRINTF("UAVTalk packet corrupt %d\r\n", header1->packet_size + 1);
|
||||
#endif
|
||||
|
||||
continue; // continue scanning for a valid packet in the buffer
|
||||
}
|
||||
|
||||
#if defined(API_DEBUG)
|
||||
DEBUG_PRINTF("UAVTalk packet found %d\r\n", header1->packet_size + 1);
|
||||
#endif
|
||||
|
||||
return (header1->packet_size + CHECKSUM_LENGTH); // return the size of the UAVTalk packet
|
||||
}
|
||||
|
||||
return -5;
|
||||
}
|
||||
|
||||
// *****************************************************************************
|
||||
|
||||
int16_t api_scanForConfigPacket(void *buf, uint16_t *len)
|
||||
{
|
||||
return -1;
|
||||
}
|
||||
|
||||
// *****************************************************************************
|
||||
// can be called from an interrupt if you wish
|
||||
|
||||
void api_1ms_tick(void)
|
||||
{ // call this once every 1ms
|
||||
|
||||
if (api_rx_timer < 0xffff) api_rx_timer++;
|
||||
if (api_tx_timer < 0xffff) api_tx_timer++;
|
||||
}
|
||||
|
||||
// *****************************************************************************
|
||||
// call this as often as possible - not from an interrupt
|
||||
|
||||
void api_process(void)
|
||||
{ // copy data from comm-port RX buffer to RF packet handler TX buffer, and from RF packet handler RX buffer to comm-port TX buffer
|
||||
|
||||
// ********************
|
||||
// decide which comm-port we are using (usart or usb)
|
||||
|
||||
bool usb_comms = false; // TRUE if we are using the usb port for comms.
|
||||
uint32_t comm_port = PIOS_COM_SERIAL; // default to using the usart comm-port
|
||||
|
||||
#if defined(PIOS_INCLUDE_USB_HID)
|
||||
if (PIOS_USB_HID_CheckAvailable(0))
|
||||
{ // USB comms is up, use the USB comm-port instead of the USART comm-port
|
||||
usb_comms = true;
|
||||
comm_port = PIOS_COM_TELEM_USB;
|
||||
}
|
||||
#endif
|
||||
|
||||
// ********************
|
||||
// check to see if the local communication port has changed (usart/usb)
|
||||
|
||||
if (api_previous_com_port == 0 && api_previous_com_port != comm_port)
|
||||
{ // the local communications port has changed .. remove any data in the buffers
|
||||
api_rx_buffer_wr = 0;
|
||||
api_tx_buffer_wr = 0;
|
||||
}
|
||||
else
|
||||
if (usb_comms)
|
||||
{ // we're using the USB for comms - keep the USART rx buffer empty
|
||||
int32_t bytes = PIOS_COM_ReceiveBufferUsed(PIOS_COM_SERIAL);
|
||||
while (bytes > 0)
|
||||
{
|
||||
PIOS_COM_ReceiveBuffer(PIOS_COM_SERIAL);
|
||||
bytes--;
|
||||
}
|
||||
}
|
||||
|
||||
api_previous_com_port = comm_port; // remember the current comm-port we are using
|
||||
|
||||
// ********************
|
||||
|
||||
uint16_t connection_index = 0; // the RF connection we are using
|
||||
|
||||
// ********************
|
||||
// send the data received from the local comm-port to the RF packet handler TX buffer
|
||||
|
||||
while (TRUE)
|
||||
{
|
||||
int16_t packet_size;
|
||||
|
||||
// free space size in the RF packet handler tx buffer
|
||||
uint16_t ph_num = ph_putData_free(connection_index);
|
||||
|
||||
// get the number of data bytes received down the comm-port
|
||||
int32_t com_num = PIOS_COM_ReceiveBufferUsed(comm_port);
|
||||
|
||||
// set the USART RTS handshaking line
|
||||
if (!usb_comms && ph_connected(connection_index))
|
||||
{
|
||||
if (ph_num < 32)
|
||||
SERIAL_RTS_CLEAR; // lower the USART RTS line - we don't have space in the buffer for anymore bytes
|
||||
else
|
||||
SERIAL_RTS_SET; // release the USART RTS line - we have space in the buffer for now bytes
|
||||
}
|
||||
else
|
||||
SERIAL_RTS_SET; // release the USART RTS line
|
||||
|
||||
// limit number of bytes we will get to how much space we have in our RX buffer
|
||||
if (com_num > sizeof(api_rx_buffer) - api_rx_buffer_wr)
|
||||
com_num = sizeof(api_rx_buffer) - api_rx_buffer_wr;
|
||||
|
||||
while (com_num > 0)
|
||||
{ // fetch a byte from the comm-port RX buffer and save it into our RX buffer
|
||||
api_rx_buffer[api_rx_buffer_wr++] = PIOS_COM_ReceiveBuffer(comm_port);
|
||||
com_num--;
|
||||
}
|
||||
|
||||
// packet_size = api_scanForConfigPacket(api_rx_buffer, &api_rx_buffer_wr);
|
||||
|
||||
packet_size = api_scanForUAVTalkPacket(api_rx_buffer, &api_rx_buffer_wr);
|
||||
if (packet_size < 0)
|
||||
break; // no UAVTalk packet in our RX buffer
|
||||
|
||||
api_rx_timer = 0;
|
||||
|
||||
if (!ph_connected(connection_index))
|
||||
{ // we don't have a link to a remote modem .. remove the UAVTalk packet from our RX buffer
|
||||
if (api_rx_buffer_wr > packet_size)
|
||||
{
|
||||
api_rx_buffer_wr -= packet_size;
|
||||
memmove(api_rx_buffer, api_rx_buffer + packet_size, api_rx_buffer_wr);
|
||||
}
|
||||
else
|
||||
api_rx_buffer_wr = 0;
|
||||
continue;
|
||||
}
|
||||
|
||||
if (ph_num < packet_size)
|
||||
break; // not enough room in the RF packet handler TX buffer for the UAVTalk packet
|
||||
|
||||
// copy the rx'ed UAVTalk packet into the RF packet handler TX buffer for sending over the RF link
|
||||
ph_putData(connection_index, api_rx_buffer, packet_size);
|
||||
|
||||
// remove the UAVTalk packet from our RX buffer
|
||||
if (api_rx_buffer_wr > packet_size)
|
||||
{
|
||||
api_rx_buffer_wr -= packet_size;
|
||||
memmove(api_rx_buffer, api_rx_buffer + packet_size, api_rx_buffer_wr);
|
||||
}
|
||||
else
|
||||
api_rx_buffer_wr = 0;
|
||||
}
|
||||
|
||||
// ********************
|
||||
// send the data received via the RF link out the comm-port
|
||||
|
||||
while (TRUE)
|
||||
{
|
||||
// get number of data bytes received via the RF link
|
||||
uint16_t ph_num = ph_getData_used(connection_index);
|
||||
|
||||
// limit to how much space we have in the temp TX buffer
|
||||
if (ph_num > sizeof(api_tx_buffer) - api_tx_buffer_wr)
|
||||
ph_num = sizeof(api_tx_buffer) - api_tx_buffer_wr;
|
||||
|
||||
if (ph_num > 0)
|
||||
{ // fetch the data bytes received via the RF link and save into our temp buffer
|
||||
ph_num = ph_getData(connection_index, api_tx_buffer + api_tx_buffer_wr, ph_num);
|
||||
api_tx_buffer_wr += ph_num;
|
||||
}
|
||||
|
||||
int16_t packet_size = api_scanForUAVTalkPacket(api_tx_buffer, &api_tx_buffer_wr);
|
||||
|
||||
if (packet_size <= 0)
|
||||
break; // no UAV Talk packet found
|
||||
|
||||
// we have a UAVTalk packet to send down the comm-port
|
||||
/*
|
||||
#if (defined(PIOS_COM_DEBUG) && (PIOS_COM_DEBUG == PIOS_COM_SERIAL))
|
||||
if (!usb_comms)
|
||||
{ // the serial-port is being used for debugging - don't send data down it
|
||||
api_tx_buffer_wr = 0;
|
||||
api_tx_timer = 0;
|
||||
continue;
|
||||
}
|
||||
#endif
|
||||
*/
|
||||
if (!usb_comms && !GPIO_IN(SERIAL_CTS_PIN))
|
||||
break; // we can't yet send data down the comm-port
|
||||
|
||||
// send the data out the comm-port
|
||||
int32_t res;
|
||||
// if (usb_comms)
|
||||
// res = PIOS_COM_SendBuffer(comm_port, api_tx_buffer, packet_size);
|
||||
// else
|
||||
res = PIOS_COM_SendBufferNonBlocking(comm_port, api_tx_buffer, packet_size); // this one doesn't work properly with USB :(
|
||||
if (res < 0)
|
||||
{ // failed to send the data out the comm-port
|
||||
#if defined(API_DEBUG)
|
||||
DEBUG_PRINTF("PIOS_COM_SendBuffer %d %d\r\n", packet_size, res);
|
||||
#endif
|
||||
|
||||
if (api_tx_timer >= 5000)
|
||||
{ // seems we can't send our data for at least the last 5 seconds - delete it
|
||||
if (api_tx_buffer_wr > packet_size)
|
||||
{
|
||||
api_tx_buffer_wr -= packet_size;
|
||||
memmove(api_tx_buffer, api_tx_buffer + packet_size, api_tx_buffer_wr);
|
||||
}
|
||||
else
|
||||
api_tx_buffer_wr = 0;
|
||||
}
|
||||
|
||||
break;
|
||||
}
|
||||
|
||||
// data was sent out the comm-port OK .. remove the sent data from our buffer
|
||||
|
||||
if (api_tx_buffer_wr > packet_size)
|
||||
{
|
||||
api_tx_buffer_wr -= packet_size;
|
||||
memmove(api_tx_buffer, api_tx_buffer + packet_size, api_tx_buffer_wr);
|
||||
}
|
||||
else
|
||||
api_tx_buffer_wr = 0;
|
||||
|
||||
api_tx_timer = 0;
|
||||
}
|
||||
|
||||
// ********************
|
||||
}
|
||||
|
||||
// *****************************************************************************
|
||||
|
||||
void api_init(void)
|
||||
{
|
||||
api_previous_com_port = 0;
|
||||
|
||||
api_rx_buffer_wr = 0;
|
||||
|
||||
api_tx_buffer_wr = 0;
|
||||
|
||||
api_rx_timer = 0;
|
||||
api_tx_timer = 0;
|
||||
}
|
||||
|
||||
// *****************************************************************************
|
@ -1,2491 +0,0 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file rfm22b.c
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @brief RF Module hardware layer
|
||||
* @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
|
||||
*/
|
||||
|
||||
// *****************************************************************
|
||||
// RFM22B hardware layer
|
||||
//
|
||||
// This module uses the RFM22B's internal packet handling hardware to encapsulate our own packet data.
|
||||
//
|
||||
// The RFM22B internal hardware packet handler configuration is as follows ..
|
||||
//
|
||||
// 4-byte (32-bit) preamble .. alternating 0's & 1's
|
||||
// 4-byte (32-bit) sync
|
||||
// 1-byte packet length (number of data bytes to follow)
|
||||
// 0 to 255 user data bytes
|
||||
//
|
||||
// Our own packet data will also contain it's own header and 32-bit CRC as a single 16-bit CRC is not sufficient for wireless comms.
|
||||
//
|
||||
// *****************************************************************
|
||||
|
||||
#include <string.h> // memmove
|
||||
|
||||
#include "stm32f10x.h"
|
||||
#include "main.h"
|
||||
#include "stopwatch.h"
|
||||
#include "gpio_in.h"
|
||||
#include "rfm22b.h"
|
||||
|
||||
#if defined(PIOS_COM_DEBUG)
|
||||
// #define RFM22_DEBUG
|
||||
// #define RFM22_INT_TIMEOUT_DEBUG
|
||||
#endif
|
||||
|
||||
// *****************************************************************
|
||||
// forward delarations
|
||||
|
||||
#if defined(RFM22_EXT_INT_USE)
|
||||
void rfm22_processInt(void);
|
||||
#endif
|
||||
|
||||
// ************************************
|
||||
// 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
|
||||
#define OSC_LOAD_CAP_2 0x7B // board 2
|
||||
#define OSC_LOAD_CAP_3 0x7E // board 3
|
||||
#define OSC_LOAD_CAP_4 0x7F // board 4
|
||||
|
||||
// ************************************
|
||||
|
||||
#define TX_TEST_MODE_TIMELIMIT_MS 30000 // TX test modes time limit (in ms)
|
||||
|
||||
//#define TX_PREAMBLE_NIBBLES 8 // 7 to 511 (number of nibbles)
|
||||
//#define RX_PREAMBLE_NIBBLES 5 // 5 to 31 (number of nibbles)
|
||||
#define TX_PREAMBLE_NIBBLES 12 // 7 to 511 (number of nibbles)
|
||||
#define RX_PREAMBLE_NIBBLES 6 // 5 to 31 (number of nibbles)
|
||||
|
||||
#define FIFO_SIZE 64 // the size of the rf modules internal FIFO buffers
|
||||
|
||||
#define TX_FIFO_HI_WATERMARK 62 // 0-63
|
||||
#define TX_FIFO_LO_WATERMARK 32 // 0-63
|
||||
|
||||
#define RX_FIFO_HI_WATERMARK 32 // 0-63
|
||||
|
||||
#define PREAMBLE_BYTE 0x55 // preamble byte (preceeds SYNC_BYTE's)
|
||||
|
||||
#define SYNC_BYTE_1 0x2D // RF sync bytes (32-bit in all)
|
||||
#define SYNC_BYTE_2 0xD4 //
|
||||
#define SYNC_BYTE_3 0x4B //
|
||||
#define SYNC_BYTE_4 0x59 //
|
||||
|
||||
// ************************************
|
||||
// the default TX power level
|
||||
|
||||
#define RFM22_DEFAULT_RF_POWER RFM22_tx_pwr_txpow_0 // +1dBm ... 1.25mW
|
||||
//#define RFM22_DEFAULT_RF_POWER RFM22_tx_pwr_txpow_1 // +2dBm ... 1.6mW
|
||||
//#define RFM22_DEFAULT_RF_POWER RFM22_tx_pwr_txpow_2 // +5dBm ... 3.16mW
|
||||
//#define RFM22_DEFAULT_RF_POWER RFM22_tx_pwr_txpow_3 // +8dBm ... 6.3mW
|
||||
//#define RFM22_DEFAULT_RF_POWER RFM22_tx_pwr_txpow_4 // +11dBm .. 12.6mW
|
||||
//#define RFM22_DEFAULT_RF_POWER RFM22_tx_pwr_txpow_5 // +14dBm .. 25mW
|
||||
//#define RFM22_DEFAULT_RF_POWER RFM22_tx_pwr_txpow_6 // +17dBm .. 50mW
|
||||
//#define RFM22_DEFAULT_RF_POWER RFM22_tx_pwr_txpow_7 // +20dBm .. 100mW
|
||||
|
||||
// ************************************
|
||||
// the default RF datarate
|
||||
|
||||
//#define RFM22_DEFAULT_RF_DATARATE 500 // 500 bits per sec
|
||||
//#define RFM22_DEFAULT_RF_DATARATE 1000 // 1k bits per sec
|
||||
//#define RFM22_DEFAULT_RF_DATARATE 2000 // 2k bits per sec
|
||||
//#define RFM22_DEFAULT_RF_DATARATE 4000 // 4k bits per sec
|
||||
//#define RFM22_DEFAULT_RF_DATARATE 8000 // 8k bits per sec
|
||||
//#define RFM22_DEFAULT_RF_DATARATE 9600 // 9.6k bits per sec
|
||||
//#define RFM22_DEFAULT_RF_DATARATE 16000 // 16k bits per sec
|
||||
//#define RFM22_DEFAULT_RF_DATARATE 19200 // 19k2 bits per sec
|
||||
//#define RFM22_DEFAULT_RF_DATARATE 24000 // 24k bits per sec
|
||||
//#define RFM22_DEFAULT_RF_DATARATE 32000 // 32k bits per sec
|
||||
//#define RFM22_DEFAULT_RF_DATARATE 64000 // 64k bits per sec
|
||||
#define RFM22_DEFAULT_RF_DATARATE 128000 // 128k bits per sec
|
||||
//#define RFM22_DEFAULT_RF_DATARATE 192000 // 192k bits per sec
|
||||
//#define RFM22_DEFAULT_RF_DATARATE 256000 // 256k bits per sec .. NOT YET WORKING
|
||||
|
||||
// ************************************
|
||||
|
||||
#define RFM22_DEFAULT_SS_RF_DATARATE 125 // 128bps
|
||||
|
||||
// ************************************
|
||||
// Normal data streaming
|
||||
// GFSK modulation
|
||||
// no manchester encoding
|
||||
// data whitening
|
||||
// FIFO mode
|
||||
// 5-nibble rx preamble length detection
|
||||
// 10-nibble tx preamble length
|
||||
// AFC enabled
|
||||
|
||||
#define LOOKUP_SIZE 14
|
||||
|
||||
// xtal 10 ppm, 434MHz
|
||||
const uint32_t data_rate[LOOKUP_SIZE] = { 500, 1000, 2000, 4000, 8000, 9600, 16000, 19200, 24000, 32000, 64000, 128000, 192000, 256000};
|
||||
const uint8_t modulation_index[LOOKUP_SIZE] = { 16, 8, 4, 2, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1};
|
||||
const uint32_t freq_deviation[LOOKUP_SIZE] = { 4000, 4000, 4000, 4000, 4000, 4800, 8000, 9600, 12000, 16000, 32000, 64000, 96000, 128000};
|
||||
const uint32_t rx_bandwidth[LOOKUP_SIZE] = { 17500, 17500, 17500, 17500, 17500, 19400, 32200, 38600, 51200, 64100, 137900, 269300, 420200, 518800};
|
||||
const int8_t est_rx_sens_dBm[LOOKUP_SIZE] = { -118, -118, -117, -116, -115, -115, -112, -112, -110, -109, -106, -103, -101, -100}; // estimated receiver sensitivity for BER = 1E-3
|
||||
|
||||
const uint8_t reg_1C[LOOKUP_SIZE] = { 0x37, 0x37, 0x37, 0x37, 0x3A, 0x3B, 0x26, 0x28, 0x2E, 0x16, 0x07, 0x83, 0x8A, 0x8C}; // rfm22_if_filter_bandwidth
|
||||
|
||||
const uint8_t reg_1D[LOOKUP_SIZE] = { 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44}; // rfm22_afc_loop_gearshift_override
|
||||
const uint8_t reg_1E[LOOKUP_SIZE] = { 0x0A, 0x0A, 0x0A, 0x0A, 0x0A, 0x0A, 0x0A, 0x0A, 0x0A, 0x0A, 0x0A, 0x0A, 0x0A, 0x02}; // rfm22_afc_timing_control
|
||||
|
||||
const uint8_t reg_1F[LOOKUP_SIZE] = { 0x03, 0x03, 0x03, 0x03, 0x03, 0x03, 0x03, 0x03, 0x03, 0x03, 0x03, 0x03, 0x03, 0x03}; // rfm22_clk_recovery_gearshift_override
|
||||
const uint8_t reg_20[LOOKUP_SIZE] = { 0xE8, 0xF4, 0xFA, 0x70, 0x3F, 0x34, 0x3F, 0x34, 0x2A, 0x3F, 0x3F, 0x5E, 0x3F, 0x2F}; // rfm22_clk_recovery_oversampling_ratio
|
||||
const uint8_t reg_21[LOOKUP_SIZE] = { 0x60, 0x20, 0x00, 0x01, 0x02, 0x02, 0x02, 0x02, 0x03, 0x02, 0x02, 0x01, 0x02, 0x02}; // rfm22_clk_recovery_offset2
|
||||
const uint8_t reg_22[LOOKUP_SIZE] = { 0x20, 0x41, 0x83, 0x06, 0x0C, 0x75, 0x0C, 0x75, 0x12, 0x0C, 0x0C, 0x5D, 0x0C, 0xBB}; // rfm22_clk_recovery_offset1
|
||||
const uint8_t reg_23[LOOKUP_SIZE] = { 0xC5, 0x89, 0x12, 0x25, 0x4A, 0x25, 0x4A, 0x25, 0x6F, 0x4A, 0x4A, 0x86, 0x4A, 0x0D}; // rfm22_clk_recovery_offset0
|
||||
const uint8_t reg_24[LOOKUP_SIZE] = { 0x00, 0x00, 0x00, 0x02, 0x07, 0x07, 0x07, 0x07, 0x07, 0x07, 0x07, 0x05, 0x07, 0x07}; // rfm22_clk_recovery_timing_loop_gain1
|
||||
const uint8_t reg_25[LOOKUP_SIZE] = { 0x0A, 0x23, 0x85, 0x0E, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x74, 0xFF, 0xFF}; // rfm22_clk_recovery_timing_loop_gain0
|
||||
|
||||
const uint8_t reg_2A[LOOKUP_SIZE] = { 0x0E, 0x0E, 0x0E, 0x0E, 0x0E, 0x0D, 0x0D, 0x0E, 0x12, 0x17, 0x31, 0x50, 0x50, 0x50}; // rfm22_afc_limiter .. AFC_pull_in_range = ±AFCLimiter[7:0] x (hbsel+1) x 625 Hz
|
||||
|
||||
const uint8_t reg_6E[LOOKUP_SIZE] = { 0x04, 0x08, 0x10, 0x20, 0x41, 0x4E, 0x83, 0x9D, 0xC4, 0x08, 0x10, 0x20, 0x31, 0x41}; // rfm22_tx_data_rate1
|
||||
const uint8_t reg_6F[LOOKUP_SIZE] = { 0x19, 0x31, 0x62, 0xC5, 0x89, 0xA5, 0x12, 0x49, 0x9C, 0x31, 0x62, 0xC5, 0x27, 0x89}; // rfm22_tx_data_rate0
|
||||
|
||||
const uint8_t reg_70[LOOKUP_SIZE] = { 0x2D, 0x2D, 0x2D, 0x2D, 0x2D, 0x2D, 0x2D, 0x2D, 0x2D, 0x0D, 0x0D, 0x0D, 0x0D, 0x0D}; // rfm22_modulation_mode_control1
|
||||
const uint8_t reg_71[LOOKUP_SIZE] = { 0x23, 0x23, 0x23, 0x23, 0x23, 0x23, 0x23, 0x23, 0x23, 0x23, 0x23, 0x23, 0x23, 0x23}; // rfm22_modulation_mode_control2
|
||||
|
||||
const uint8_t reg_72[LOOKUP_SIZE] = { 0x06, 0x06, 0x06, 0x06, 0x06, 0x08, 0x0D, 0x0F, 0x13, 0x1A, 0x33, 0x66, 0x9A, 0xCD}; // rfm22_frequency_deviation
|
||||
|
||||
// ************************************
|
||||
// Scan Spectrum settings
|
||||
// GFSK modulation
|
||||
// no manchester encoding
|
||||
// data whitening
|
||||
// FIFO mode
|
||||
// 5-nibble rx preamble length detection
|
||||
// 10-nibble tx preamble length
|
||||
// AFC disabled
|
||||
|
||||
#define SS_LOOKUP_SIZE 2
|
||||
|
||||
// xtal 1 ppm, 434MHz
|
||||
const uint32_t ss_rx_bandwidth[SS_LOOKUP_SIZE] = { 2600, 10600};
|
||||
|
||||
const uint8_t ss_reg_1C[SS_LOOKUP_SIZE] = { 0x51, 0x32}; // rfm22_if_filter_bandwidth
|
||||
const uint8_t ss_reg_1D[SS_LOOKUP_SIZE] = { 0x00, 0x00}; // rfm22_afc_loop_gearshift_override
|
||||
|
||||
const uint8_t ss_reg_20[SS_LOOKUP_SIZE] = { 0xE8, 0x38}; // rfm22_clk_recovery_oversampling_ratio
|
||||
const uint8_t ss_reg_21[SS_LOOKUP_SIZE] = { 0x60, 0x02}; // rfm22_clk_recovery_offset2
|
||||
const uint8_t ss_reg_22[SS_LOOKUP_SIZE] = { 0x20, 0x4D}; // rfm22_clk_recovery_offset1
|
||||
const uint8_t ss_reg_23[SS_LOOKUP_SIZE] = { 0xC5, 0xD3}; // rfm22_clk_recovery_offset0
|
||||
const uint8_t ss_reg_24[SS_LOOKUP_SIZE] = { 0x00, 0x07}; // rfm22_clk_recovery_timing_loop_gain1
|
||||
const uint8_t ss_reg_25[SS_LOOKUP_SIZE] = { 0x0F, 0xFF}; // rfm22_clk_recovery_timing_loop_gain0
|
||||
|
||||
const uint8_t ss_reg_2A[SS_LOOKUP_SIZE] = { 0xFF, 0xFF}; // rfm22_afc_limiter .. AFC_pull_in_range = ±AFCLimiter[7:0] x (hbsel+1) x 625 Hz
|
||||
|
||||
const uint8_t ss_reg_70[SS_LOOKUP_SIZE] = { 0x24, 0x2D}; // rfm22_modulation_mode_control1
|
||||
const uint8_t ss_reg_71[SS_LOOKUP_SIZE] = { 0x2B, 0x23}; // rfm22_modulation_mode_control2
|
||||
|
||||
// ************************************
|
||||
|
||||
volatile bool initialized = false;
|
||||
|
||||
#if defined(RFM22_EXT_INT_USE)
|
||||
volatile bool exec_using_spi; // set this if you want to access the SPI bus outside of the interrupt
|
||||
volatile bool inside_ext_int; // this is set whenever we are inside the interrupt
|
||||
#endif
|
||||
|
||||
uint8_t device_type; // the RF chips device ID number
|
||||
uint8_t device_version; // the RF chips revision number
|
||||
|
||||
volatile uint8_t rf_mode; // holds our current RF mode
|
||||
|
||||
uint32_t lower_carrier_frequency_limit_Hz; // the minimum RF frequency we can use
|
||||
uint32_t upper_carrier_frequency_limit_Hz; // the maximum RF frequency we can use
|
||||
uint32_t carrier_frequency_hz; // the current RF frequency we are on
|
||||
|
||||
uint32_t carrier_datarate_bps; // the RF data rate we are using
|
||||
|
||||
uint32_t rf_bandwidth_used; // the RF bandwidth currently used
|
||||
uint32_t ss_rf_bandwidth_used; // the RF bandwidth currently used
|
||||
|
||||
uint8_t hbsel; // holds the hbsel (1 or 2)
|
||||
float frequency_step_size; // holds the minimum frequency step size
|
||||
|
||||
uint8_t frequency_hop_channel; // current frequency hop channel
|
||||
|
||||
uint8_t frequency_hop_step_size_reg; //
|
||||
|
||||
uint8_t adc_config; // holds the adc config reg value
|
||||
|
||||
volatile uint8_t device_status; // device status register
|
||||
volatile uint8_t int_status1; // interrupt status register 1
|
||||
volatile uint8_t int_status2; // interrupt status register 2
|
||||
volatile uint8_t ezmac_status; // ezmac status register
|
||||
|
||||
volatile int16_t afc_correction; // afc correction reading
|
||||
volatile int32_t afc_correction_Hz; // afc correction reading (in Hz)
|
||||
|
||||
volatile int16_t temperature_reg; // the temperature sensor reading
|
||||
|
||||
#if defined(RFM22_DEBUG)
|
||||
volatile uint8_t prev_device_status; // just for debugging
|
||||
volatile uint8_t prev_int_status1; // " "
|
||||
volatile uint8_t prev_int_status2; // " "
|
||||
volatile uint8_t prev_ezmac_status; // " "
|
||||
|
||||
bool debug_outputted;
|
||||
#endif
|
||||
|
||||
volatile uint8_t osc_load_cap; // xtal frequency calibration value
|
||||
|
||||
volatile uint8_t rssi; // the current RSSI (register value)
|
||||
volatile int16_t rssi_dBm; // dBm value
|
||||
|
||||
uint8_t tx_power; // the transmit power to use for data transmissions
|
||||
volatile uint8_t tx_pwr; // the tx power register read back
|
||||
|
||||
volatile uint8_t rx_buffer_current; // the current receive buffer in use (double buffer)
|
||||
volatile uint8_t rx_buffer[256] __attribute__ ((aligned(4))); // the receive buffer .. received packet data is saved here
|
||||
volatile uint16_t rx_buffer_wr; // the receive buffer write index
|
||||
|
||||
volatile uint8_t rx_packet_buf[256] __attribute__ ((aligned(4))); // the received packet
|
||||
volatile uint16_t rx_packet_wr; // the receive packet write index
|
||||
volatile int16_t rx_packet_start_rssi_dBm; //
|
||||
volatile int32_t rx_packet_start_afc_Hz; //
|
||||
volatile int16_t rx_packet_rssi_dBm; // the received packet signal strength
|
||||
volatile int32_t rx_packet_afc_Hz; // the receive packet frequency offset
|
||||
|
||||
volatile uint8_t *tx_data_addr; // the address of the data we send in the transmitted packets
|
||||
volatile uint16_t tx_data_rd; // the tx data read index
|
||||
volatile uint16_t tx_data_wr; // the tx data write index
|
||||
|
||||
//volatile uint8_t tx_fifo[FIFO_SIZE]; //
|
||||
|
||||
volatile uint8_t rx_fifo[FIFO_SIZE]; //
|
||||
volatile uint8_t rx_fifo_wr; //
|
||||
|
||||
int lookup_index;
|
||||
int ss_lookup_index;
|
||||
|
||||
volatile bool power_on_reset; // set if the RF module has reset itself
|
||||
|
||||
volatile uint16_t rfm22_int_timer; // used to detect if the RF module stops responding. thus act accordingly if it does stop responding.
|
||||
volatile uint16_t rfm22_int_time_outs; // counter
|
||||
volatile uint16_t prev_rfm22_int_time_outs; //
|
||||
|
||||
uint32_t clear_channel_count = (TX_PREAMBLE_NIBBLES + 4) * 2; // minimum clear channel time before allowing transmit
|
||||
|
||||
uint16_t timeout_ms = 20000; //
|
||||
uint16_t timeout_sync_ms = 3; //
|
||||
uint16_t timeout_data_ms = 20; //
|
||||
|
||||
t_rfm22_TxDataByteCallback tx_data_byte_callback_function = NULL;
|
||||
t_rfm22_RxDataCallback rx_data_callback_function = NULL;
|
||||
|
||||
// ************************************
|
||||
// SPI read/write
|
||||
|
||||
void rfm22_startBurstWrite(uint8_t addr)
|
||||
{
|
||||
// wait 1us .. so we don't toggle the CS line to quickly
|
||||
PIOS_DELAY_WaituS(1);
|
||||
|
||||
// chip select line LOW
|
||||
PIOS_SPI_RC_PinSet(RFM22_PIOS_SPI, 0);
|
||||
|
||||
PIOS_SPI_TransferByte(RFM22_PIOS_SPI, 0x80 | addr);
|
||||
}
|
||||
|
||||
inline void rfm22_burstWrite(uint8_t data)
|
||||
{
|
||||
PIOS_SPI_TransferByte(RFM22_PIOS_SPI, data);
|
||||
}
|
||||
|
||||
void rfm22_endBurstWrite(void)
|
||||
{
|
||||
// chip select line HIGH
|
||||
PIOS_SPI_RC_PinSet(RFM22_PIOS_SPI, 1);
|
||||
}
|
||||
|
||||
void rfm22_write(uint8_t addr, uint8_t data)
|
||||
{
|
||||
// wait 1us .. so we don't toggle the CS line to quickly
|
||||
PIOS_DELAY_WaituS(1);
|
||||
|
||||
// chip select line LOW
|
||||
PIOS_SPI_RC_PinSet(RFM22_PIOS_SPI, 0);
|
||||
|
||||
PIOS_SPI_TransferByte(RFM22_PIOS_SPI, 0x80 | addr);
|
||||
PIOS_SPI_TransferByte(RFM22_PIOS_SPI, data);
|
||||
|
||||
// chip select line HIGH
|
||||
PIOS_SPI_RC_PinSet(RFM22_PIOS_SPI, 1);
|
||||
}
|
||||
|
||||
void rfm22_startBurstRead(uint8_t addr)
|
||||
{
|
||||
// wait 1us .. so we don't toggle the CS line to quickly
|
||||
PIOS_DELAY_WaituS(1);
|
||||
|
||||
// chip select line LOW
|
||||
PIOS_SPI_RC_PinSet(RFM22_PIOS_SPI, 0);
|
||||
|
||||
PIOS_SPI_TransferByte(RFM22_PIOS_SPI, addr & 0x7f);
|
||||
}
|
||||
|
||||
inline uint8_t rfm22_burstRead(void)
|
||||
{
|
||||
return PIOS_SPI_TransferByte(RFM22_PIOS_SPI, 0xff);
|
||||
}
|
||||
|
||||
void rfm22_endBurstRead(void)
|
||||
{
|
||||
// chip select line HIGH
|
||||
PIOS_SPI_RC_PinSet(RFM22_PIOS_SPI, 1);
|
||||
}
|
||||
|
||||
uint8_t rfm22_read(uint8_t addr)
|
||||
{
|
||||
uint8_t rdata;
|
||||
|
||||
// wait 1us .. so we don't toggle the CS line to quickly
|
||||
PIOS_DELAY_WaituS(1);
|
||||
|
||||
// chip select line LOW
|
||||
PIOS_SPI_RC_PinSet(RFM22_PIOS_SPI, 0);
|
||||
|
||||
PIOS_SPI_TransferByte(RFM22_PIOS_SPI, addr & 0x7f);
|
||||
rdata = PIOS_SPI_TransferByte(RFM22_PIOS_SPI, 0xff);
|
||||
|
||||
// chip select line HIGH
|
||||
PIOS_SPI_RC_PinSet(RFM22_PIOS_SPI, 1);
|
||||
|
||||
return rdata;
|
||||
}
|
||||
|
||||
// ************************************
|
||||
// external interrupt
|
||||
|
||||
#if defined(RFM22_EXT_INT_USE)
|
||||
|
||||
void RFM22_EXT_INT_FUNC(void)
|
||||
{
|
||||
inside_ext_int = TRUE;
|
||||
|
||||
if (EXTI_GetITStatus(RFM22_EXT_INT_LINE) != RESET)
|
||||
{
|
||||
// Clear the EXTI line pending bit
|
||||
EXTI_ClearITPendingBit(RFM22_EXT_INT_LINE);
|
||||
|
||||
// USB_LED_TOGGLE; // TEST ONLY
|
||||
|
||||
if (!booting && !exec_using_spi)
|
||||
{
|
||||
// while (!GPIO_IN(RF_INT_PIN) && !exec_using_spi)
|
||||
{ // stay here until the interrupt line returns HIGH
|
||||
rfm22_processInt();
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
inside_ext_int = FALSE;
|
||||
}
|
||||
|
||||
void rfm22_disableExtInt(void)
|
||||
{
|
||||
// Configure the external interrupt
|
||||
GPIO_EXTILineConfig(RFM22_EXT_INT_PORT_SOURCE, RFM22_EXT_INT_PIN_SOURCE);
|
||||
EXTI_InitTypeDef EXTI_InitStructure;
|
||||
EXTI_InitStructure.EXTI_Line = RFM22_EXT_INT_LINE;
|
||||
EXTI_InitStructure.EXTI_Mode = EXTI_Mode_Interrupt;
|
||||
EXTI_InitStructure.EXTI_Trigger = EXTI_Trigger_Falling;
|
||||
EXTI_InitStructure.EXTI_LineCmd = DISABLE;
|
||||
EXTI_Init(&EXTI_InitStructure);
|
||||
|
||||
EXTI_ClearFlag(RFM22_EXT_INT_LINE);
|
||||
}
|
||||
|
||||
void rfm22_enableExtInt(void)
|
||||
{
|
||||
// Configure the external interrupt
|
||||
GPIO_EXTILineConfig(RFM22_EXT_INT_PORT_SOURCE, RFM22_EXT_INT_PIN_SOURCE);
|
||||
EXTI_InitTypeDef EXTI_InitStructure;
|
||||
EXTI_InitStructure.EXTI_Line = RFM22_EXT_INT_LINE;
|
||||
EXTI_InitStructure.EXTI_Mode = EXTI_Mode_Interrupt;
|
||||
EXTI_InitStructure.EXTI_Trigger = EXTI_Trigger_Falling;
|
||||
EXTI_InitStructure.EXTI_LineCmd = ENABLE;
|
||||
EXTI_Init(&EXTI_InitStructure);
|
||||
|
||||
EXTI_ClearFlag(RFM22_EXT_INT_LINE);
|
||||
|
||||
// Enable and set the external interrupt
|
||||
NVIC_InitTypeDef NVIC_InitStructure;
|
||||
NVIC_InitStructure.NVIC_IRQChannel = RFM22_EXT_INT_IRQn;
|
||||
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = RFM22_EXT_INT_PRIORITY;
|
||||
NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0;
|
||||
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
|
||||
NVIC_Init(&NVIC_InitStructure);
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
// ************************************
|
||||
// set/get the current tx power setting
|
||||
|
||||
void rfm22_setTxPower(uint8_t tx_pwr)
|
||||
{
|
||||
switch (tx_pwr)
|
||||
{
|
||||
case 0: tx_power = RFM22_tx_pwr_txpow_0; break; // +1dBm ... 1.25mW
|
||||
case 1: tx_power = RFM22_tx_pwr_txpow_1; break; // +2dBm ... 1.6mW
|
||||
case 2: tx_power = RFM22_tx_pwr_txpow_2; break; // +5dBm ... 3.16mW
|
||||
case 3: tx_power = RFM22_tx_pwr_txpow_3; break; // +8dBm ... 6.3mW
|
||||
case 4: tx_power = RFM22_tx_pwr_txpow_4; break; // +11dBm .. 12.6mW
|
||||
case 5: tx_power = RFM22_tx_pwr_txpow_5; break; // +14dBm .. 25mW
|
||||
case 6: tx_power = RFM22_tx_pwr_txpow_6; break; // +17dBm .. 50mW
|
||||
case 7: tx_power = RFM22_tx_pwr_txpow_7; break; // +20dBm .. 100mW
|
||||
default: break;
|
||||
}
|
||||
}
|
||||
|
||||
uint8_t rfm22_getTxPower(void)
|
||||
{
|
||||
return tx_power;
|
||||
}
|
||||
|
||||
// ************************************
|
||||
|
||||
uint32_t rfm22_minFrequency(void)
|
||||
{
|
||||
return lower_carrier_frequency_limit_Hz;
|
||||
}
|
||||
uint32_t rfm22_maxFrequency(void)
|
||||
{
|
||||
return upper_carrier_frequency_limit_Hz;
|
||||
}
|
||||
|
||||
void rfm22_setNominalCarrierFrequency(uint32_t frequency_hz)
|
||||
{
|
||||
|
||||
#if defined(RFM22_EXT_INT_USE)
|
||||
exec_using_spi = TRUE;
|
||||
#endif
|
||||
|
||||
// *******
|
||||
|
||||
if (frequency_hz < lower_carrier_frequency_limit_Hz) frequency_hz = lower_carrier_frequency_limit_Hz;
|
||||
else
|
||||
if (frequency_hz > upper_carrier_frequency_limit_Hz) frequency_hz = upper_carrier_frequency_limit_Hz;
|
||||
|
||||
if (frequency_hz < 480000000)
|
||||
hbsel = 1;
|
||||
else
|
||||
hbsel = 2;
|
||||
uint8_t fb = (uint8_t)(frequency_hz / (10000000 * hbsel));
|
||||
|
||||
uint32_t fc = (uint32_t)(frequency_hz - (10000000 * hbsel * fb));
|
||||
|
||||
fc = (fc * 64u) / (10000ul * hbsel);
|
||||
fb -= 24;
|
||||
|
||||
// carrier_frequency_hz = frequency_hz;
|
||||
carrier_frequency_hz = ((uint32_t)fb + 24 + ((float)fc / 64000)) * 10000000 * hbsel;
|
||||
|
||||
if (hbsel > 1)
|
||||
fb |= RFM22_fbs_hbsel;
|
||||
|
||||
fb |= RFM22_fbs_sbse; // is this the RX LO polarity?
|
||||
|
||||
frequency_step_size = 156.25f * hbsel;
|
||||
|
||||
rfm22_write(RFM22_frequency_hopping_channel_select, frequency_hop_channel); // frequency hopping channel (0-255)
|
||||
|
||||
rfm22_write(RFM22_frequency_offset1, 0); // no frequency offset
|
||||
rfm22_write(RFM22_frequency_offset2, 0); // no frequency offset
|
||||
|
||||
rfm22_write(RFM22_frequency_band_select, fb); // set the carrier frequency
|
||||
rfm22_write(RFM22_nominal_carrier_frequency1, fc >> 8); // " "
|
||||
rfm22_write(RFM22_nominal_carrier_frequency0, fc & 0xff); // " "
|
||||
|
||||
// *******
|
||||
|
||||
#if defined(RFM22_DEBUG)
|
||||
DEBUG_PRINTF("rf setFreq: %u\r\n", carrier_frequency_hz);
|
||||
// DEBUG_PRINTF("rf setFreq frequency_step_size: %0.2f\r\n", frequency_step_size);
|
||||
#endif
|
||||
|
||||
#if defined(RFM22_EXT_INT_USE)
|
||||
exec_using_spi = FALSE;
|
||||
#endif
|
||||
}
|
||||
|
||||
uint32_t rfm22_getNominalCarrierFrequency(void)
|
||||
{
|
||||
return carrier_frequency_hz;
|
||||
}
|
||||
|
||||
float rfm22_getFrequencyStepSize(void)
|
||||
{
|
||||
return frequency_step_size;
|
||||
}
|
||||
|
||||
void rfm22_setFreqHopChannel(uint8_t channel)
|
||||
{ // set the frequency hopping channel
|
||||
frequency_hop_channel = channel;
|
||||
rfm22_write(RFM22_frequency_hopping_channel_select, frequency_hop_channel);
|
||||
}
|
||||
|
||||
uint8_t rfm22_freqHopChannel(void)
|
||||
{ // return the current frequency hopping channel
|
||||
return frequency_hop_channel;
|
||||
}
|
||||
|
||||
uint32_t rfm22_freqHopSize(void)
|
||||
{ // return the frequency hopping step size
|
||||
return ((uint32_t)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 datarate_bps, bool data_whitening)
|
||||
{
|
||||
|
||||
#if defined(RFM22_EXT_INT_USE)
|
||||
exec_using_spi = TRUE;
|
||||
#endif
|
||||
// *******
|
||||
|
||||
lookup_index = 0;
|
||||
while (lookup_index < (LOOKUP_SIZE - 1) && data_rate[lookup_index] < datarate_bps)
|
||||
lookup_index++;
|
||||
|
||||
carrier_datarate_bps = datarate_bps = data_rate[lookup_index];
|
||||
|
||||
rf_bandwidth_used = rx_bandwidth[lookup_index];
|
||||
|
||||
// ********************************
|
||||
|
||||
#if defined(RFM22_DEBUG)
|
||||
uint32_t frequency_deviation = freq_deviation[lookup_index]; // Hz
|
||||
uint32_t modulation_bandwidth = datarate_bps + (2 * frequency_deviation);
|
||||
#endif
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
rfm22_write(0x1C, reg_1C[lookup_index]); // rfm22_if_filter_bandwidth
|
||||
|
||||
rfm22_write(0x1D, reg_1D[lookup_index]); // rfm22_afc_loop_gearshift_override
|
||||
rfm22_write(0x1E, reg_1E[lookup_index]); // RFM22_afc_timing_control
|
||||
|
||||
rfm22_write(0x1F, reg_1F[lookup_index]); // RFM22_clk_recovery_gearshift_override
|
||||
rfm22_write(0x20, reg_20[lookup_index]); // rfm22_clk_recovery_oversampling_ratio
|
||||
rfm22_write(0x21, reg_21[lookup_index]); // rfm22_clk_recovery_offset2
|
||||
rfm22_write(0x22, reg_22[lookup_index]); // rfm22_clk_recovery_offset1
|
||||
rfm22_write(0x23, reg_23[lookup_index]); // rfm22_clk_recovery_offset0
|
||||
rfm22_write(0x24, reg_24[lookup_index]); // rfm22_clk_recovery_timing_loop_gain1
|
||||
rfm22_write(0x25, reg_25[lookup_index]); // rfm22_clk_recovery_timing_loop_gain0
|
||||
|
||||
rfm22_write(0x2A, reg_2A[lookup_index]); // rfm22_afc_limiter
|
||||
|
||||
if (carrier_datarate_bps < 100000)
|
||||
rfm22_write(0x58, 0x80); // rfm22_chargepump_current_trimming_override
|
||||
else
|
||||
rfm22_write(0x58, 0xC0); // rfm22_chargepump_current_trimming_override
|
||||
|
||||
rfm22_write(0x6E, reg_6E[lookup_index]); // rfm22_tx_data_rate1
|
||||
rfm22_write(0x6F, reg_6F[lookup_index]); // rfm22_tx_data_rate0
|
||||
|
||||
// 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_write(0x70, reg_70[lookup_index] & ~RFM22_mmc1_enwhite); // rfm22_modulation_mode_control1
|
||||
else
|
||||
rfm22_write(0x70, reg_70[lookup_index] | RFM22_mmc1_enwhite); // rfm22_modulation_mode_control1
|
||||
|
||||
rfm22_write(0x71, reg_71[lookup_index]); // rfm22_modulation_mode_control2
|
||||
|
||||
rfm22_write(0x72, reg_72[lookup_index]); // rfm22_frequency_deviation
|
||||
|
||||
rfm22_write(RFM22_ook_counter_value1, 0x00);
|
||||
rfm22_write(RFM22_ook_counter_value2, 0x00);
|
||||
|
||||
// ********************************
|
||||
// calculate the TX register values
|
||||
/*
|
||||
uint16_t fd = frequency_deviation / 625;
|
||||
|
||||
uint8_t mmc1 = RFM22_mmc1_enphpwdn | RFM22_mmc1_manppol;
|
||||
uint16_t txdr;
|
||||
if (datarate_bps < 30000)
|
||||
{
|
||||
txdr = (datarate_bps * 20972) / 10000;
|
||||
mmc1 |= RFM22_mmc1_txdtrtscale;
|
||||
}
|
||||
else
|
||||
txdr = (datarate_bps * 6553) / 100000;
|
||||
|
||||
uint8_t mmc2 = RFM22_mmc2_dtmod_fifo | RFM22_mmc2_modtyp_gfsk; // FIFO mode, GFSK
|
||||
// uint8_t mmc2 = RFM22_mmc2_dtmod_pn9 | RFM22_mmc2_modtyp_gfsk; // PN9 mode, GFSK .. TX TEST MODE
|
||||
if (fd & 0x100) mmc2 |= RFM22_mmc2_fd;
|
||||
|
||||
rfm22_write(RFM22_frequency_deviation, fd); // set the TX peak frequency deviation
|
||||
|
||||
rfm22_write(RFM22_modulation_mode_control1, mmc1);
|
||||
rfm22_write(RFM22_modulation_mode_control2, mmc2);
|
||||
|
||||
rfm22_write(RFM22_tx_data_rate1, txdr >> 8); // set the TX data rate
|
||||
rfm22_write(RFM22_tx_data_rate0, txdr); // " "
|
||||
*/
|
||||
// ********************************
|
||||
// determine a clear channel time
|
||||
|
||||
// initialise the stopwatch with a suitable resolution for the datarate
|
||||
STOPWATCH_init(4000000ul / carrier_datarate_bps); // set resolution to the time for 1 nibble (4-bits) at rf datarate
|
||||
|
||||
// ********************************
|
||||
// determine suitable time-out periods
|
||||
|
||||
timeout_sync_ms = (8000ul * 16) / carrier_datarate_bps; // milliseconds
|
||||
if (timeout_sync_ms < 3)
|
||||
timeout_sync_ms = 3; // because out timer resolution is only 1ms
|
||||
|
||||
timeout_data_ms = (8000ul * 100) / carrier_datarate_bps; // milliseconds
|
||||
if (timeout_data_ms < 3)
|
||||
timeout_data_ms = 3; // because out timer resolution is only 1ms
|
||||
|
||||
// ********************************
|
||||
|
||||
#if defined(RFM22_DEBUG)
|
||||
DEBUG_PRINTF("rf datarate_bps: %d\r\n", datarate_bps);
|
||||
DEBUG_PRINTF("rf frequency_deviation: %d\r\n", frequency_deviation);
|
||||
DEBUG_PRINTF("rf modulation_bandwidth: %u\r\n", modulation_bandwidth);
|
||||
DEBUG_PRINTF("rf_rx_bandwidth[%u]: %u\r\n", lookup_index, rx_bandwidth[lookup_index]);
|
||||
DEBUG_PRINTF("rf est rx sensitivity[%u]: %ddBm\r\n", lookup_index, est_rx_sens_dBm[lookup_index]);
|
||||
#endif
|
||||
|
||||
// *******
|
||||
|
||||
#if defined(RFM22_EXT_INT_USE)
|
||||
exec_using_spi = FALSE;
|
||||
#endif
|
||||
}
|
||||
|
||||
uint32_t rfm22_getDatarate(void)
|
||||
{
|
||||
return carrier_datarate_bps;
|
||||
}
|
||||
|
||||
// ************************************
|
||||
|
||||
void rfm22_setSSBandwidth(uint32_t bandwidth_index)
|
||||
{
|
||||
|
||||
#if defined(RFM22_EXT_INT_USE)
|
||||
exec_using_spi = TRUE;
|
||||
#endif
|
||||
// *******
|
||||
|
||||
ss_lookup_index = bandwidth_index;
|
||||
|
||||
ss_rf_bandwidth_used = ss_rx_bandwidth[lookup_index];
|
||||
|
||||
// ********************************
|
||||
|
||||
rfm22_write(0x1C, ss_reg_1C[ss_lookup_index]); // rfm22_if_filter_bandwidth
|
||||
rfm22_write(0x1D, ss_reg_1D[ss_lookup_index]); // rfm22_afc_loop_gearshift_override
|
||||
|
||||
rfm22_write(0x20, ss_reg_20[ss_lookup_index]); // rfm22_clk_recovery_oversampling_ratio
|
||||
rfm22_write(0x21, ss_reg_21[ss_lookup_index]); // rfm22_clk_recovery_offset2
|
||||
rfm22_write(0x22, ss_reg_22[ss_lookup_index]); // rfm22_clk_recovery_offset1
|
||||
rfm22_write(0x23, ss_reg_23[ss_lookup_index]); // rfm22_clk_recovery_offset0
|
||||
rfm22_write(0x24, ss_reg_24[ss_lookup_index]); // rfm22_clk_recovery_timing_loop_gain1
|
||||
rfm22_write(0x25, ss_reg_25[ss_lookup_index]); // rfm22_clk_recovery_timing_loop_gain0
|
||||
|
||||
rfm22_write(0x2A, ss_reg_2A[ss_lookup_index]); // rfm22_afc_limiter
|
||||
|
||||
rfm22_write(0x58, 0x80); // rfm22_chargepump_current_trimming_override
|
||||
|
||||
rfm22_write(0x70, ss_reg_70[ss_lookup_index]); // rfm22_modulation_mode_control1
|
||||
rfm22_write(0x71, ss_reg_71[ss_lookup_index]); // rfm22_modulation_mode_control2
|
||||
|
||||
rfm22_write(RFM22_ook_counter_value1, 0x00);
|
||||
rfm22_write(RFM22_ook_counter_value2, 0x00);
|
||||
|
||||
// ********************************
|
||||
|
||||
#if defined(RFM22_DEBUG)
|
||||
DEBUG_PRINTF("ss_rf_rx_bandwidth[%u]: %u\r\n", ss_lookup_index, ss_rx_bandwidth[ss_lookup_index]);
|
||||
#endif
|
||||
|
||||
// *******
|
||||
|
||||
#if defined(RFM22_EXT_INT_USE)
|
||||
exec_using_spi = FALSE;
|
||||
#endif
|
||||
}
|
||||
|
||||
// ************************************
|
||||
|
||||
void rfm22_setRxMode(uint8_t mode, bool multi_packet_mode)
|
||||
{
|
||||
#if defined(RFM22_EXT_INT_USE)
|
||||
exec_using_spi = TRUE;
|
||||
#endif
|
||||
|
||||
// disable interrupts
|
||||
rfm22_write(RFM22_interrupt_enable1, 0x00);
|
||||
rfm22_write(RFM22_interrupt_enable2, 0x00);
|
||||
|
||||
// disable the receiver and transmitter
|
||||
// rfm22_write(RFM22_op_and_func_ctrl1, RFM22_opfc1_xton); // READY mode
|
||||
rfm22_write(RFM22_op_and_func_ctrl1, RFM22_opfc1_pllon); // TUNE mode
|
||||
|
||||
RX_LED_OFF;
|
||||
TX_LED_OFF;
|
||||
|
||||
// rfm22_write(RFM22_rx_fifo_control, RX_FIFO_HI_WATERMARK); // RX FIFO Almost Full Threshold (0 - 63)
|
||||
|
||||
if (rf_mode == TX_CARRIER_MODE || rf_mode == TX_PN_MODE)
|
||||
{ // 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 | RFM22_mmc2_modtyp_gfsk);
|
||||
}
|
||||
|
||||
rx_buffer_wr = 0; // empty the rx buffer
|
||||
|
||||
rfm22_int_timer = 0; // reset the timer
|
||||
|
||||
rf_mode = mode;
|
||||
|
||||
if (mode != RX_SCAN_SPECTRUM)
|
||||
{
|
||||
STOPWATCH_reset(); // reset clear channel detect timer
|
||||
|
||||
// enable RX interrupts
|
||||
rfm22_write(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_ie2_enswdet);
|
||||
}
|
||||
|
||||
// read interrupt status - clear interrupts
|
||||
rfm22_read(RFM22_interrupt_status1);
|
||||
rfm22_read(RFM22_interrupt_status2);
|
||||
|
||||
// clear FIFOs
|
||||
if (!multi_packet_mode)
|
||||
{
|
||||
rfm22_write(RFM22_op_and_func_ctrl2, RFM22_opfc2_ffclrrx | RFM22_opfc2_ffclrtx);
|
||||
rfm22_write(RFM22_op_and_func_ctrl2, 0x00);
|
||||
}
|
||||
else
|
||||
{
|
||||
rfm22_write(RFM22_op_and_func_ctrl2, RFM22_opfc2_rxmpk | RFM22_opfc2_ffclrrx | RFM22_opfc2_ffclrtx);
|
||||
rfm22_write(RFM22_op_and_func_ctrl2, RFM22_opfc2_rxmpk);
|
||||
}
|
||||
|
||||
// enable the receiver
|
||||
// rfm22_write(RFM22_op_and_func_ctrl1, RFM22_opfc1_xton | RFM22_opfc1_rxon);
|
||||
rfm22_write(RFM22_op_and_func_ctrl1, RFM22_opfc1_pllon | RFM22_opfc1_rxon);
|
||||
|
||||
#if defined(RFM22_EXT_INT_USE)
|
||||
exec_using_spi = FALSE;
|
||||
#endif
|
||||
|
||||
#if defined(RFM22_DEBUG)
|
||||
DEBUG_PRINTF(" RX Mode\r\n");
|
||||
#endif
|
||||
}
|
||||
|
||||
// ************************************
|
||||
|
||||
uint16_t rfm22_addHeader(uint8_t mode)
|
||||
{
|
||||
uint16_t i = 0;
|
||||
|
||||
if (mode == TX_STREAM_MODE)
|
||||
{ // add header
|
||||
for (uint16_t j = (TX_PREAMBLE_NIBBLES + 1) / 2; j > 0; j--)
|
||||
{
|
||||
rfm22_burstWrite(PREAMBLE_BYTE);
|
||||
i++;
|
||||
}
|
||||
rfm22_burstWrite(SYNC_BYTE_1); i++;
|
||||
rfm22_burstWrite(SYNC_BYTE_2); i++;
|
||||
}
|
||||
|
||||
return i;
|
||||
}
|
||||
|
||||
// ************************************
|
||||
|
||||
void rfm22_setTxMode(uint8_t mode)
|
||||
{
|
||||
if (mode != TX_DATA_MODE && mode != TX_STREAM_MODE && mode != TX_CARRIER_MODE && mode != TX_PN_MODE)
|
||||
return; // invalid mode
|
||||
|
||||
#if defined(RFM22_EXT_INT_USE)
|
||||
exec_using_spi = TRUE;
|
||||
#endif
|
||||
|
||||
// *******************
|
||||
|
||||
// disable interrupts
|
||||
rfm22_write(RFM22_interrupt_enable1, 0x00);
|
||||
rfm22_write(RFM22_interrupt_enable2, 0x00);
|
||||
|
||||
// rfm22_write(RFM22_op_and_func_ctrl1, RFM22_opfc1_xton); // READY mode
|
||||
rfm22_write(RFM22_op_and_func_ctrl1, RFM22_opfc1_pllon); // TUNE mode
|
||||
|
||||
RX_LED_OFF;
|
||||
|
||||
// set the tx power
|
||||
// rfm22_write(RFM22_tx_power, RFM22_tx_pwr_lna_sw | tx_power);
|
||||
// rfm22_write(RFM22_tx_power, RFM22_tx_pwr_papeaken | RFM22_tx_pwr_papeaklvl_0 | RFM22_tx_pwr_lna_sw | 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 | tx_power);
|
||||
|
||||
uint8_t fd_bit = rfm22_read(RFM22_modulation_mode_control2) & RFM22_mmc2_fd;
|
||||
if (mode == TX_CARRIER_MODE)
|
||||
{ // blank carrier mode - for testing
|
||||
rfm22_write(RFM22_modulation_mode_control2, fd_bit | RFM22_mmc2_dtmod_pn9 | RFM22_mmc2_modtyp_none); // FIFO mode, Blank carrier
|
||||
}
|
||||
else
|
||||
if (mode == TX_PN_MODE)
|
||||
{ // psuedo random data carrier mode - for testing
|
||||
rfm22_write(RFM22_modulation_mode_control2, fd_bit | RFM22_mmc2_dtmod_pn9 | RFM22_mmc2_modtyp_gfsk); // FIFO mode, PN9 carrier
|
||||
}
|
||||
else
|
||||
{ // data transmission
|
||||
rfm22_write(RFM22_modulation_mode_control2, fd_bit | RFM22_mmc2_dtmod_fifo | RFM22_mmc2_modtyp_gfsk); // FIFO mode, GFSK modulation
|
||||
}
|
||||
|
||||
// rfm22_write(0x72, reg_72[lookup_index]); // rfm22_frequency_deviation
|
||||
|
||||
// clear FIFOs
|
||||
rfm22_write(RFM22_op_and_func_ctrl2, RFM22_opfc2_ffclrrx | RFM22_opfc2_ffclrtx);
|
||||
rfm22_write(RFM22_op_and_func_ctrl2, 0x00);
|
||||
|
||||
// *******************
|
||||
// add some data to the chips TX FIFO before enabling the transmitter
|
||||
|
||||
{
|
||||
uint16_t rd = 0;
|
||||
uint16_t wr = tx_data_wr;
|
||||
if (!tx_data_addr) wr = 0;
|
||||
|
||||
if (mode == TX_DATA_MODE)
|
||||
rfm22_write(RFM22_transmit_packet_length, wr); // set the total number of data bytes we are going to transmit
|
||||
|
||||
uint16_t max_bytes = FIFO_SIZE - 1;
|
||||
|
||||
uint16_t i = 0;
|
||||
|
||||
rfm22_startBurstWrite(RFM22_fifo_access);
|
||||
|
||||
if (mode == TX_STREAM_MODE)
|
||||
{
|
||||
if (rd >= wr)
|
||||
{ // no data to send - yet .. just send preamble pattern
|
||||
while (true)
|
||||
{
|
||||
rfm22_burstWrite(PREAMBLE_BYTE);
|
||||
if (++i >= max_bytes) break;
|
||||
}
|
||||
}
|
||||
else
|
||||
{ // add the RF heaader
|
||||
i += rfm22_addHeader(mode);
|
||||
}
|
||||
}
|
||||
|
||||
// add some data
|
||||
for (uint16_t j = wr - rd; j > 0; j--)
|
||||
{
|
||||
// int16_t b = -1;
|
||||
// if (tx_data_byte_callback_function)
|
||||
// b = tx_data_byte_callback_function();
|
||||
|
||||
rfm22_burstWrite(tx_data_addr[rd++]);
|
||||
if (++i >= max_bytes) break;
|
||||
}
|
||||
|
||||
rfm22_endBurstWrite();
|
||||
|
||||
tx_data_rd = rd;
|
||||
}
|
||||
|
||||
// *******************
|
||||
|
||||
rfm22_int_timer = 0; // reset the timer
|
||||
|
||||
rf_mode = mode;
|
||||
|
||||
// enable TX interrupts
|
||||
// rfm22_write(RFM22_interrupt_enable1, RFM22_ie1_enpksent | RFM22_ie1_entxffaem | RFM22_ie1_enfferr);
|
||||
rfm22_write(RFM22_interrupt_enable1, RFM22_ie1_enpksent | RFM22_ie1_entxffaem);
|
||||
|
||||
// read interrupt status - clear interrupts
|
||||
rfm22_read(RFM22_interrupt_status1);
|
||||
rfm22_read(RFM22_interrupt_status2);
|
||||
|
||||
// enable the transmitter
|
||||
// rfm22_write(RFM22_op_and_func_ctrl1, RFM22_opfc1_xton | RFM22_opfc1_txon);
|
||||
rfm22_write(RFM22_op_and_func_ctrl1, RFM22_opfc1_pllon | RFM22_opfc1_txon);
|
||||
|
||||
TX_LED_ON;
|
||||
|
||||
// *******************
|
||||
// create new slightly random clear channel detector count value
|
||||
|
||||
uint32_t ccc = (TX_PREAMBLE_NIBBLES + 8) + 4; // minimum clear channel time before allowing transmit
|
||||
clear_channel_count = ccc + (random32 % (ccc * 2)); // plus a some randomness
|
||||
|
||||
// *******************
|
||||
|
||||
#if defined(RFM22_EXT_INT_USE)
|
||||
exec_using_spi = FALSE;
|
||||
#endif
|
||||
|
||||
#if defined(RFM22_DEBUG)
|
||||
if (rf_mode == TX_DATA_MODE) DEBUG_PRINTF(" TX_Data_Mode\r\n");
|
||||
else
|
||||
if (rf_mode == TX_STREAM_MODE) DEBUG_PRINTF(" TX_Stream_Mode\r\n");
|
||||
else
|
||||
if (rf_mode == TX_CARRIER_MODE) DEBUG_PRINTF(" TX_Carrier_Mode\r\n");
|
||||
else
|
||||
if (rf_mode == TX_PN_MODE) DEBUG_PRINTF(" TX_PN_Mode\r\n");
|
||||
#endif
|
||||
}
|
||||
|
||||
// ************************************
|
||||
// external interrupt line triggered (or polled) from the rf chip
|
||||
|
||||
void rfm22_processRxInt(void)
|
||||
{
|
||||
register uint8_t int_stat1 = int_status1;
|
||||
register uint8_t int_stat2 = int_status2;
|
||||
|
||||
if (int_stat2 & RFM22_is2_ipreaval)
|
||||
{ // Valid preamble detected
|
||||
|
||||
if (rf_mode == RX_WAIT_PREAMBLE_MODE)
|
||||
{
|
||||
rfm22_int_timer = 0; // reset the timer
|
||||
rf_mode = RX_WAIT_SYNC_MODE;
|
||||
RX_LED_ON;
|
||||
|
||||
#if defined(RFM22_DEBUG) && !defined(RFM22_EXT_INT_USE)
|
||||
DEBUG_PRINTF(" pream_det");
|
||||
debug_outputted = true;
|
||||
#endif
|
||||
}
|
||||
}
|
||||
/* else
|
||||
if (int_stat2 & RFM22_is2_ipreainval)
|
||||
{ // Invalid preamble detected
|
||||
|
||||
if (rf_mode == RX_WAIT_SYNC_MODE)
|
||||
{
|
||||
#if defined(RFM22_DEBUG) && !defined(RFM22_EXT_INT_USE)
|
||||
DEBUG_PRINTF(" invalid_preamble");
|
||||
debug_outputted = true;
|
||||
#endif
|
||||
|
||||
rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false);
|
||||
return;
|
||||
}
|
||||
else
|
||||
{
|
||||
}
|
||||
}
|
||||
*/
|
||||
if (int_stat2 & RFM22_is2_iswdet)
|
||||
{ // Sync word detected
|
||||
|
||||
STOPWATCH_reset(); // reset timer
|
||||
|
||||
if (rf_mode == RX_WAIT_PREAMBLE_MODE || rf_mode == RX_WAIT_SYNC_MODE)
|
||||
{
|
||||
rfm22_int_timer = 0; // reset the timer
|
||||
rf_mode = RX_DATA_MODE;
|
||||
RX_LED_ON;
|
||||
|
||||
// read the 10-bit signed afc correction value
|
||||
afc_correction = (uint16_t)rfm22_read(RFM22_afc_correction_read) << 8; // bits 9 to 2
|
||||
afc_correction |= (uint16_t)rfm22_read(RFM22_ook_counter_value1) & 0x00c0; // bits 1 & 0
|
||||
afc_correction >>= 6;
|
||||
afc_correction_Hz = (int32_t)(frequency_step_size * afc_correction + 0.5f); // convert the afc value to Hz
|
||||
|
||||
rx_packet_start_rssi_dBm = rssi_dBm; // remember the rssi for this packet
|
||||
rx_packet_start_afc_Hz = afc_correction_Hz; // remember the afc value for this packet
|
||||
|
||||
#if defined(RFM22_DEBUG) && !defined(RFM22_EXT_INT_USE)
|
||||
DEBUG_PRINTF(" sync_det");
|
||||
DEBUG_PRINTF(" AFC_%d_%dHz", afc_correction, afc_correction_Hz);
|
||||
debug_outputted = true;
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
||||
if (int_stat1 & RFM22_is1_irxffafull)
|
||||
{ // RX FIFO almost full, it needs emptying
|
||||
|
||||
if (rf_mode == RX_DATA_MODE)
|
||||
{ // read data from the rf chips FIFO buffer
|
||||
rfm22_int_timer = 0; // reset the timer
|
||||
|
||||
register uint16_t len = rfm22_read(RFM22_received_packet_length); // read the total length of the packet data
|
||||
|
||||
register uint16_t wr = rx_buffer_wr;
|
||||
|
||||
if ((wr + RX_FIFO_HI_WATERMARK) > len)
|
||||
{ // some kind of error in the RF module
|
||||
#if defined(RFM22_DEBUG) && !defined(RFM22_EXT_INT_USE)
|
||||
DEBUG_PRINTF(" r_size_error1");
|
||||
debug_outputted = true;
|
||||
#endif
|
||||
|
||||
rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false);
|
||||
return;
|
||||
}
|
||||
|
||||
if (((wr + RX_FIFO_HI_WATERMARK) >= len) && !(int_stat1 & RFM22_is1_ipkvalid))
|
||||
{ // some kind of error in the RF module
|
||||
#if defined(RFM22_DEBUG) && !defined(RFM22_EXT_INT_USE)
|
||||
DEBUG_PRINTF(" r_size_error2");
|
||||
debug_outputted = true;
|
||||
#endif
|
||||
|
||||
rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false);
|
||||
return;
|
||||
}
|
||||
|
||||
// fetch the rx'ed data from the rf chips RX FIFO
|
||||
rfm22_startBurstRead(RFM22_fifo_access);
|
||||
rx_fifo_wr = 0;
|
||||
for (register uint8_t i = RX_FIFO_HI_WATERMARK; i > 0; i--)
|
||||
rx_fifo[rx_fifo_wr++] = rfm22_burstRead(); // read a byte from the rf modules RX FIFO buffer
|
||||
rfm22_endBurstRead();
|
||||
|
||||
uint16_t i = rx_fifo_wr;
|
||||
if (wr + i > sizeof(rx_buffer)) i = sizeof(rx_buffer) - wr;
|
||||
memcpy((void *)(rx_buffer + wr), (void *)rx_fifo, i); // save the new bytes into our rx buffer
|
||||
wr += i;
|
||||
|
||||
rx_buffer_wr = wr;
|
||||
|
||||
if (rx_data_callback_function)
|
||||
{ // pass the new data onto whoever wanted it
|
||||
if (!rx_data_callback_function((void *)rx_fifo, rx_fifo_wr))
|
||||
{
|
||||
rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false);
|
||||
return;
|
||||
}
|
||||
}
|
||||
|
||||
#if defined(RFM22_DEBUG) && !defined(RFM22_EXT_INT_USE)
|
||||
// DEBUG_PRINTF(" r_data_%u/%u", rx_buffer_wr, len);
|
||||
// debug_outputted = true;
|
||||
#endif
|
||||
}
|
||||
else
|
||||
{ // just clear the RX FIFO
|
||||
rfm22_startBurstRead(RFM22_fifo_access);
|
||||
for (register uint16_t i = RX_FIFO_HI_WATERMARK; i > 0; i--)
|
||||
rfm22_burstRead(); // read a byte from the rf modules RX FIFO buffer
|
||||
rfm22_endBurstRead();
|
||||
}
|
||||
}
|
||||
|
||||
if (int_stat1 & RFM22_is1_icrerror)
|
||||
{ // CRC error .. discard the received data
|
||||
|
||||
if (rf_mode == RX_DATA_MODE)
|
||||
{
|
||||
rfm22_int_timer = 0; // reset the timer
|
||||
|
||||
#if defined(RFM22_DEBUG) && !defined(RFM22_EXT_INT_USE)
|
||||
DEBUG_PRINTF(" CRC_ERR");
|
||||
debug_outputted = true;
|
||||
#endif
|
||||
|
||||
rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false); // reset the receiver
|
||||
return;
|
||||
}
|
||||
}
|
||||
|
||||
// if (int_stat2 & RFM22_is2_irssi)
|
||||
// { // RSSI level is >= the set threshold
|
||||
// }
|
||||
|
||||
// if (device_status & RFM22_ds_rxffem)
|
||||
// { // RX FIFO empty
|
||||
// }
|
||||
|
||||
// if (device_status & RFM22_ds_headerr)
|
||||
// { // Header check error
|
||||
// }
|
||||
|
||||
if (int_stat1 & RFM22_is1_ipkvalid)
|
||||
{ // Valid packet received
|
||||
|
||||
if (rf_mode == RX_DATA_MODE)
|
||||
{
|
||||
rfm22_int_timer = 0; // reset the timer
|
||||
|
||||
// disable the receiver
|
||||
// rfm22_write(RFM22_op_and_func_ctrl1, RFM22_opfc1_xton); // READY mode
|
||||
rfm22_write(RFM22_op_and_func_ctrl1, RFM22_opfc1_pllon); // TUNE mode
|
||||
|
||||
register uint16_t len = rfm22_read(RFM22_received_packet_length); // read the total length of the packet data
|
||||
|
||||
register uint16_t wr = rx_buffer_wr;
|
||||
|
||||
if (wr < len)
|
||||
{ // their must still be data in the RX FIFO we need to get
|
||||
|
||||
// fetch the rx'ed data from the rf chips RX FIFO
|
||||
rfm22_startBurstRead(RFM22_fifo_access);
|
||||
rx_fifo_wr = 0;
|
||||
for (register uint8_t i = len - wr; i > 0; i--)
|
||||
rx_fifo[rx_fifo_wr++] = rfm22_burstRead(); // read a byte from the rf modules RX FIFO buffer
|
||||
rfm22_endBurstRead();
|
||||
|
||||
uint16_t i = rx_fifo_wr;
|
||||
if (wr + i > sizeof(rx_buffer)) i = sizeof(rx_buffer) - wr;
|
||||
memcpy((void *)(rx_buffer + wr), (void *)rx_fifo, i); // save the new bytes into our rx buffer
|
||||
wr += i;
|
||||
|
||||
rx_buffer_wr = wr;
|
||||
|
||||
if (rx_data_callback_function)
|
||||
{ // pass the new data onto whoever wanted it
|
||||
if (!rx_data_callback_function((void *)rx_fifo, rx_fifo_wr))
|
||||
{
|
||||
// rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false);
|
||||
// return;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false); // reset the receiver
|
||||
|
||||
if (wr != len)
|
||||
{ // we have a packet length error .. discard the packet
|
||||
#if defined(RFM22_DEBUG) && !defined(RFM22_EXT_INT_USE)
|
||||
DEBUG_PRINTF(" r_pack_len_error_%u_%u", len, wr);
|
||||
debug_outputted = true;
|
||||
#endif
|
||||
|
||||
return;
|
||||
}
|
||||
|
||||
// we have a valid received packet
|
||||
#if defined(RFM22_DEBUG) && !defined(RFM22_EXT_INT_USE)
|
||||
DEBUG_PRINTF(" VALID_R_PACKET_%u", wr);
|
||||
debug_outputted = true;
|
||||
#endif
|
||||
|
||||
if (rx_packet_wr == 0)
|
||||
{ // save the received packet for further processing
|
||||
rx_packet_rssi_dBm = rx_packet_start_rssi_dBm; // remember the rssi for this packet
|
||||
rx_packet_afc_Hz = rx_packet_start_afc_Hz; // remember the afc offset for this packet
|
||||
memmove((void *)rx_packet_buf, (void *)rx_buffer, wr); // copy the packet data
|
||||
rx_packet_wr = wr; // save the length of the data
|
||||
}
|
||||
else
|
||||
{ // the save buffer is still in use .. nothing we can do but to drop the packet
|
||||
}
|
||||
|
||||
// return;
|
||||
}
|
||||
else
|
||||
{
|
||||
// rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false); // reset the receiver
|
||||
// return;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
uint8_t rfm22_topUpRFTxFIFO(void)
|
||||
{
|
||||
rfm22_int_timer = 0; // reset the timer
|
||||
|
||||
uint16_t rd = tx_data_rd;
|
||||
uint16_t wr = tx_data_wr;
|
||||
|
||||
if (rf_mode == TX_DATA_MODE && (!tx_data_addr || rd >= wr))
|
||||
return 0; // no more data to send
|
||||
|
||||
uint16_t max_bytes = FIFO_SIZE - TX_FIFO_LO_WATERMARK - 1;
|
||||
|
||||
uint16_t i = 0;
|
||||
|
||||
// top-up the rf chips TX FIFO buffer
|
||||
rfm22_startBurstWrite(RFM22_fifo_access);
|
||||
|
||||
// add some data
|
||||
for (uint16_t j = wr - rd; j > 0; j--)
|
||||
{
|
||||
// int16_t b = -1;
|
||||
// if (tx_data_byte_callback_function)
|
||||
// b = tx_data_byte_callback_function();
|
||||
|
||||
rfm22_burstWrite(tx_data_addr[rd++]);
|
||||
if (++i >= max_bytes) break;
|
||||
}
|
||||
tx_data_rd = rd;
|
||||
|
||||
if (rf_mode == TX_STREAM_MODE && rd >= wr)
|
||||
{ // all data sent .. need to start sending RF header again
|
||||
|
||||
tx_data_addr = NULL;
|
||||
tx_data_rd = tx_data_wr = 0;
|
||||
|
||||
while (i < max_bytes)
|
||||
{
|
||||
rfm22_burstWrite(PREAMBLE_BYTE); // preamble byte
|
||||
i++;
|
||||
}
|
||||
|
||||
// todo:
|
||||
|
||||
// add the RF heaader
|
||||
// i += rfm22_addHeader(rf_mode);
|
||||
}
|
||||
|
||||
rfm22_endBurstWrite();
|
||||
|
||||
#if defined(RFM22_DEBUG) && !defined(RFM22_EXT_INT_USE)
|
||||
// DEBUG_PRINTF(" added_%d_bytes", i);
|
||||
// debug_outputted = true;
|
||||
#endif
|
||||
|
||||
return i;
|
||||
}
|
||||
|
||||
void rfm22_processTxInt(void)
|
||||
{
|
||||
register uint8_t int_stat1 = int_status1;
|
||||
// register uint8_t int_stat2 = int_status2;
|
||||
|
||||
/*
|
||||
if (int_stat1 & RFM22_is1_ifferr)
|
||||
{ // FIFO underflow/overflow error
|
||||
rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false);
|
||||
tx_data_addr = NULL;
|
||||
tx_data_rd = tx_data_wr = 0;
|
||||
return;
|
||||
}
|
||||
*/
|
||||
|
||||
if (int_stat1 & RFM22_is1_ixtffaem)
|
||||
{ // TX FIFO almost empty, it needs filling up
|
||||
|
||||
#if defined(RFM22_DEBUG) && !defined(RFM22_EXT_INT_USE)
|
||||
// DEBUG_PRINTF(" T_FIFO_AE");
|
||||
// debug_outputted = true;
|
||||
#endif
|
||||
|
||||
// uint8_t bytes_added = rfm22_topUpRFTxFIFO();
|
||||
rfm22_topUpRFTxFIFO();
|
||||
}
|
||||
|
||||
if (int_stat1 & RFM22_is1_ipksent)
|
||||
{ // Packet has been sent
|
||||
#if defined(RFM22_DEBUG) && !defined(RFM22_EXT_INT_USE)
|
||||
DEBUG_PRINTF(" T_Sent");
|
||||
debug_outputted = true;
|
||||
#endif
|
||||
|
||||
if (rf_mode == TX_DATA_MODE)
|
||||
{
|
||||
rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false); // back to receive mode
|
||||
|
||||
tx_data_addr = NULL;
|
||||
tx_data_rd = tx_data_wr = 0;
|
||||
return;
|
||||
}
|
||||
else
|
||||
if (rf_mode == TX_STREAM_MODE)
|
||||
{
|
||||
tx_data_addr = NULL;
|
||||
tx_data_rd = tx_data_wr = 0;
|
||||
|
||||
rfm22_setTxMode(TX_STREAM_MODE);
|
||||
return;
|
||||
}
|
||||
}
|
||||
|
||||
// if (int_stat1 & RFM22_is1_itxffafull)
|
||||
// { // TX FIFO almost full, it needs to be transmitted
|
||||
// }
|
||||
}
|
||||
|
||||
void rfm22_processInt(void)
|
||||
{ // this is called from the external interrupt handler
|
||||
|
||||
#if !defined(RFM22_EXT_INT_USE)
|
||||
if (GPIO_IN(RF_INT_PIN))
|
||||
return; // the external int line is high (no signalled interrupt)
|
||||
#endif
|
||||
|
||||
if (!initialized || power_on_reset)
|
||||
return; // we haven't yet been initialized
|
||||
|
||||
#if defined(RFM22_DEBUG)
|
||||
debug_outputted = false;
|
||||
#endif
|
||||
|
||||
// ********************************
|
||||
// read the RF modules current status registers
|
||||
|
||||
// read device status register
|
||||
device_status = rfm22_read(RFM22_device_status);
|
||||
|
||||
// read ezmac status register
|
||||
ezmac_status = rfm22_read(RFM22_ezmac_status);
|
||||
|
||||
// read interrupt status registers - clears the interrupt line
|
||||
int_status1 = rfm22_read(RFM22_interrupt_status1);
|
||||
int_status2 = rfm22_read(RFM22_interrupt_status2);
|
||||
|
||||
if (rf_mode != TX_DATA_MODE && rf_mode != TX_STREAM_MODE && rf_mode != TX_CARRIER_MODE && rf_mode != TX_PN_MODE)
|
||||
{
|
||||
rssi = rfm22_read(RFM22_rssi); // read rx signal strength .. 45 = -100dBm, 205 = -20dBm
|
||||
rssi_dBm = ((int16_t)rssi / 2) - 122; // convert to dBm
|
||||
|
||||
// calibrate the RSSI value (rf bandwidth appears to affect it)
|
||||
// if (rf_bandwidth_used > 0)
|
||||
// rssi_dBm -= 10000 / rf_bandwidth_used;
|
||||
}
|
||||
else
|
||||
{
|
||||
tx_pwr = rfm22_read(RFM22_tx_power); // read the tx power register
|
||||
}
|
||||
|
||||
if (int_status2 & RFM22_is2_ipor)
|
||||
{ // the RF module has gone and done a reset - we need to re-initialize the rf module
|
||||
initialized = FALSE;
|
||||
power_on_reset = TRUE;
|
||||
return;
|
||||
}
|
||||
|
||||
// ********************************
|
||||
// debug stuff
|
||||
|
||||
#if defined(RFM22_DEBUG) && !defined(RFM22_EXT_INT_USE)
|
||||
if (prev_device_status != device_status || prev_int_status1 != int_status1 || prev_int_status2 != int_status2 || prev_ezmac_status != ezmac_status)
|
||||
{
|
||||
DEBUG_PRINTF("%02x %02x %02x %02x %dC", device_status, int_status1, int_status2, ezmac_status, temperature_reg);
|
||||
|
||||
if ((device_status & RFM22_ds_cps_mask) == RFM22_ds_cps_rx)
|
||||
DEBUG_PRINTF(" %ddBm", rssi_dBm); // rx mode
|
||||
else
|
||||
if ((device_status & RFM22_ds_cps_mask) == RFM22_ds_cps_tx)
|
||||
DEBUG_PRINTF(" %s", (tx_pwr & RFM22_tx_pwr_papeakval) ? "ANT_MISMATCH" : "ant_ok"); // tx mode
|
||||
|
||||
debug_outputted = true;
|
||||
|
||||
prev_device_status = device_status;
|
||||
prev_int_status1 = int_status1;
|
||||
prev_int_status2 = int_status2;
|
||||
prev_ezmac_status = ezmac_status;
|
||||
}
|
||||
#endif
|
||||
|
||||
// ********************************
|
||||
// read the ADC - temperature sensor .. this can only be used in IDLE mode
|
||||
/*
|
||||
if (!(rfm22_read(RFM22_adc_config) & RFM22_ac_adcstartbusy))
|
||||
{ // the ADC has completed it's conversion
|
||||
|
||||
// read the ADC sample
|
||||
temperature_reg = (int16_t)rfm22_read(RFM22_adc_value) * 0.5f - 64;
|
||||
|
||||
// start a new ADC conversion
|
||||
rfm22_write(RFM22_adc_config, adc_config | RFM22_ac_adcstartbusy);
|
||||
|
||||
#if defined(RFM22_DEBUG) && !defined(RFM22_EXT_INT_USE)
|
||||
DEBUG_PRINTF(", %dC", temperature_reg);
|
||||
debug_outputted = true;
|
||||
#endif
|
||||
}
|
||||
*/
|
||||
// ********************************
|
||||
|
||||
register uint16_t timer_ms = rfm22_int_timer;
|
||||
|
||||
switch (rf_mode)
|
||||
{
|
||||
case RX_SCAN_SPECTRUM:
|
||||
break;
|
||||
|
||||
case RX_WAIT_PREAMBLE_MODE:
|
||||
case RX_WAIT_SYNC_MODE:
|
||||
case RX_DATA_MODE:
|
||||
|
||||
if (device_status & (RFM22_ds_ffunfl | RFM22_ds_ffovfl))
|
||||
{ // FIFO under/over flow error
|
||||
|
||||
#if defined(RFM22_DEBUG) && !defined(RFM22_EXT_INT_USE)
|
||||
DEBUG_PRINTF(" R_UNDER/OVERRUN");
|
||||
debug_outputted = true;
|
||||
#endif
|
||||
|
||||
rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false); // reset the receiver
|
||||
tx_data_rd = tx_data_wr = 0; // wipe TX buffer
|
||||
break;
|
||||
}
|
||||
|
||||
if (rf_mode == RX_WAIT_SYNC_MODE && timer_ms >= timeout_sync_ms)
|
||||
{
|
||||
rfm22_int_time_outs++;
|
||||
|
||||
#if defined(RFM22_DEBUG) && !defined(RFM22_EXT_INT_USE)
|
||||
DEBUG_PRINTF(" R_SYNC_TIMEOUT");
|
||||
debug_outputted = true;
|
||||
#endif
|
||||
|
||||
rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false); // reset the receiver
|
||||
tx_data_rd = tx_data_wr = 0; // wipe TX buffer
|
||||
break;
|
||||
}
|
||||
|
||||
if (rf_mode == RX_DATA_MODE && timer_ms >= timeout_data_ms)
|
||||
{ // missing interrupts
|
||||
rfm22_int_time_outs++;
|
||||
rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false); // reset the receiver
|
||||
tx_data_rd = tx_data_wr = 0; // wipe TX buffer
|
||||
break;
|
||||
}
|
||||
|
||||
if ((device_status & RFM22_ds_cps_mask) != RFM22_ds_cps_rx)
|
||||
{ // the rf module is not in rx mode
|
||||
if (timer_ms >= 100)
|
||||
{
|
||||
rfm22_int_time_outs++;
|
||||
|
||||
#if defined(RFM22_DEBUG) && !defined(RFM22_EXT_INT_USE)
|
||||
DEBUG_PRINTF(" R_TIMEOUT");
|
||||
debug_outputted = true;
|
||||
#endif
|
||||
|
||||
rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false); // reset the receiver
|
||||
tx_data_rd = tx_data_wr = 0; // wipe TX buffer
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
rfm22_processRxInt(); // process the interrupt
|
||||
break;
|
||||
|
||||
case TX_DATA_MODE:
|
||||
|
||||
if (device_status & (RFM22_ds_ffunfl | RFM22_ds_ffovfl))
|
||||
{ // FIFO under/over flow error
|
||||
|
||||
#if defined(RFM22_DEBUG) && !defined(RFM22_EXT_INT_USE)
|
||||
DEBUG_PRINTF(" T_UNDER/OVERRUN");
|
||||
debug_outputted = true;
|
||||
#endif
|
||||
|
||||
rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false); // back to rx mode
|
||||
tx_data_rd = tx_data_wr = 0; // wipe TX buffer
|
||||
break;
|
||||
}
|
||||
|
||||
if (timer_ms >= timeout_data_ms)
|
||||
{
|
||||
rfm22_int_time_outs++;
|
||||
rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false); // back to rx mode
|
||||
tx_data_rd = tx_data_wr = 0; // wipe TX buffer
|
||||
break;
|
||||
}
|
||||
|
||||
if ((device_status & RFM22_ds_cps_mask) != RFM22_ds_cps_tx)
|
||||
{ // the rf module is not in tx mode
|
||||
if (timer_ms >= 100)
|
||||
{
|
||||
rfm22_int_time_outs++;
|
||||
|
||||
#if defined(RFM22_DEBUG) && !defined(RFM22_EXT_INT_USE)
|
||||
DEBUG_PRINTF(" T_TIMEOUT");
|
||||
debug_outputted = true;
|
||||
#endif
|
||||
|
||||
rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false); // back to rx mode
|
||||
tx_data_rd = tx_data_wr = 0; // wipe TX buffer
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
rfm22_processTxInt(); // process the interrupt
|
||||
break;
|
||||
|
||||
case TX_STREAM_MODE:
|
||||
|
||||
// todo:
|
||||
rfm22_processTxInt(); // process the interrupt
|
||||
|
||||
break;
|
||||
|
||||
case TX_CARRIER_MODE:
|
||||
case TX_PN_MODE:
|
||||
|
||||
// if (timer_ms >= TX_TEST_MODE_TIMELIMIT_MS) // 'nn'ms limit
|
||||
// {
|
||||
// rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false); // back to rx mode
|
||||
// tx_data_rd = tx_data_wr = 0; // wipe TX buffer
|
||||
// break;
|
||||
// }
|
||||
|
||||
break;
|
||||
|
||||
default: // unknown mode - this should NEVER happen, maybe we should do a complete CPU reset here
|
||||
rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false); // to rx mode
|
||||
tx_data_rd = tx_data_wr = 0; // wipe TX buffer
|
||||
break;
|
||||
}
|
||||
|
||||
// ********************************
|
||||
|
||||
#if defined(RFM22_DEBUG) && !defined(RFM22_EXT_INT_USE)
|
||||
if (debug_outputted)
|
||||
{
|
||||
switch (rf_mode)
|
||||
{
|
||||
case RX_SCAN_SPECTRUM:
|
||||
DEBUG_PRINTF(" R_SCAN_SPECTRUM\r\n");
|
||||
break;
|
||||
case RX_WAIT_PREAMBLE_MODE:
|
||||
DEBUG_PRINTF(" R_WAIT_PREAMBLE\r\n");
|
||||
break;
|
||||
case RX_WAIT_SYNC_MODE:
|
||||
DEBUG_PRINTF(" R_WAIT_SYNC\r\n");
|
||||
break;
|
||||
case RX_DATA_MODE:
|
||||
DEBUG_PRINTF(" R_DATA\r\n");
|
||||
break;
|
||||
case TX_DATA_MODE:
|
||||
DEBUG_PRINTF(" T_DATA\r\n");
|
||||
break;
|
||||
case TX_STREAM_MODE:
|
||||
DEBUG_PRINTF(" T_STREAM\r\n");
|
||||
break;
|
||||
case TX_CARRIER_MODE:
|
||||
DEBUG_PRINTF(" T_CARRIER\r\n");
|
||||
break;
|
||||
case TX_PN_MODE:
|
||||
DEBUG_PRINTF(" T_PN\r\n");
|
||||
break;
|
||||
default:
|
||||
DEBUG_PRINTF(" UNKNOWN_MODE\r\n");
|
||||
break;
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
// ********************************
|
||||
}
|
||||
|
||||
// ************************************
|
||||
|
||||
int16_t rfm22_getRSSI(void)
|
||||
{
|
||||
#if defined(RFM22_EXT_INT_USE)
|
||||
exec_using_spi = TRUE;
|
||||
#endif
|
||||
|
||||
rssi = rfm22_read(RFM22_rssi); // read rx signal strength .. 45 = -100dBm, 205 = -20dBm
|
||||
rssi_dBm = ((int16_t)rssi / 2) - 122; // convert to dBm
|
||||
|
||||
#if defined(RFM22_EXT_INT_USE)
|
||||
exec_using_spi = FALSE;
|
||||
#endif
|
||||
|
||||
return rssi_dBm;
|
||||
}
|
||||
|
||||
int16_t rfm22_receivedRSSI(void)
|
||||
{ // return the packets signal strength
|
||||
if (!initialized)
|
||||
return -200;
|
||||
else
|
||||
return rx_packet_rssi_dBm;
|
||||
}
|
||||
|
||||
int32_t rfm22_receivedAFCHz(void)
|
||||
{ // return the packets offset frequency
|
||||
if (!initialized)
|
||||
return 0;
|
||||
else
|
||||
return rx_packet_afc_Hz;
|
||||
}
|
||||
|
||||
uint16_t rfm22_receivedLength(void)
|
||||
{ // return the size of the data received
|
||||
if (!initialized)
|
||||
return 0;
|
||||
else
|
||||
return rx_packet_wr;
|
||||
}
|
||||
|
||||
uint8_t * rfm22_receivedPointer(void)
|
||||
{ // return the address of the data
|
||||
return (uint8_t *)&rx_packet_buf;
|
||||
}
|
||||
|
||||
void rfm22_receivedDone(void)
|
||||
{ // empty the rx packet buffer
|
||||
rx_packet_wr = 0;
|
||||
}
|
||||
|
||||
// ************************************
|
||||
|
||||
int32_t rfm22_sendData(void *data, uint16_t length, bool send_immediately)
|
||||
{
|
||||
if (!initialized)
|
||||
return -1; // we are not yet initialized
|
||||
|
||||
if (length == 0)
|
||||
return -2; // no data to send
|
||||
|
||||
if (!data || length > 255)
|
||||
return -3; // no data or too much data to send
|
||||
|
||||
if (tx_data_wr > 0)
|
||||
return -4; // already have data to be sent
|
||||
|
||||
if (rf_mode == TX_DATA_MODE || rf_mode == TX_STREAM_MODE || rf_mode == TX_CARRIER_MODE || rf_mode == TX_PN_MODE || rf_mode == RX_SCAN_SPECTRUM)
|
||||
return -5; // we are currently transmitting or scanning the spectrum
|
||||
|
||||
tx_data_addr = data;
|
||||
tx_data_rd = 0;
|
||||
tx_data_wr = length;
|
||||
|
||||
#if defined(RFM22_DEBUG)
|
||||
DEBUG_PRINTF("rf sendData(0x%08x %u)\r\n", (uint32_t)tx_data_addr, tx_data_wr);
|
||||
#endif
|
||||
|
||||
if (send_immediately || rfm22_channelIsClear()) // is the channel clear to transmit on?
|
||||
rfm22_setTxMode(TX_DATA_MODE); // transmit NOW
|
||||
|
||||
return tx_data_wr;
|
||||
}
|
||||
|
||||
// ************************************
|
||||
|
||||
void rfm22_setTxStream(void) // TEST ONLY
|
||||
{
|
||||
if (!initialized)
|
||||
return;
|
||||
|
||||
tx_data_rd = tx_data_wr = 0;
|
||||
|
||||
rfm22_setTxMode(TX_STREAM_MODE);
|
||||
}
|
||||
|
||||
// ************************************
|
||||
|
||||
void rfm22_setTxNormal(void)
|
||||
{
|
||||
if (!initialized)
|
||||
return;
|
||||
|
||||
// if (rf_mode == TX_CARRIER_MODE || rf_mode == TX_PN_MODE)
|
||||
if (rf_mode != RX_SCAN_SPECTRUM)
|
||||
{
|
||||
rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false);
|
||||
tx_data_rd = tx_data_wr = 0;
|
||||
|
||||
rx_packet_wr = 0;
|
||||
rx_packet_start_rssi_dBm = 0;
|
||||
rx_packet_start_afc_Hz = 0;
|
||||
rx_packet_rssi_dBm = 0;
|
||||
rx_packet_afc_Hz = 0;
|
||||
}
|
||||
}
|
||||
|
||||
// enable a blank tx carrier (for frequency alignment)
|
||||
void rfm22_setTxCarrierMode(void)
|
||||
{
|
||||
if (!initialized)
|
||||
return;
|
||||
|
||||
if (rf_mode != TX_CARRIER_MODE && rf_mode != RX_SCAN_SPECTRUM)
|
||||
rfm22_setTxMode(TX_CARRIER_MODE);
|
||||
}
|
||||
|
||||
// enable a psuedo random data tx carrier (for spectrum inspection)
|
||||
void rfm22_setTxPNMode(void)
|
||||
{
|
||||
if (!initialized)
|
||||
return;
|
||||
|
||||
if (rf_mode != TX_PN_MODE && rf_mode != RX_SCAN_SPECTRUM)
|
||||
rfm22_setTxMode(TX_PN_MODE);
|
||||
}
|
||||
|
||||
// ************************************
|
||||
|
||||
// return the current mode
|
||||
int8_t rfm22_currentMode(void)
|
||||
{
|
||||
return rf_mode;
|
||||
}
|
||||
|
||||
// return TRUE if we are transmitting
|
||||
bool rfm22_transmitting(void)
|
||||
{
|
||||
return (rf_mode == TX_DATA_MODE || rf_mode == TX_STREAM_MODE || rf_mode == TX_CARRIER_MODE || rf_mode == TX_PN_MODE);
|
||||
}
|
||||
|
||||
// return TRUE if the channel is clear to transmit on
|
||||
bool rfm22_channelIsClear(void)
|
||||
{
|
||||
if (!initialized)
|
||||
return FALSE; // we haven't yet been initialized
|
||||
|
||||
if (rf_mode != RX_WAIT_PREAMBLE_MODE && rf_mode != RX_WAIT_SYNC_MODE)
|
||||
return FALSE; // we are receiving something or we are transmitting or we are scanning the spectrum
|
||||
|
||||
return TRUE;
|
||||
// return (STOPWATCH_get_count() > clear_channel_count);
|
||||
}
|
||||
|
||||
// return TRUE if the transmiter is ready for use
|
||||
bool rfm22_txReady(void)
|
||||
{
|
||||
if (!initialized)
|
||||
return FALSE; // we haven't yet been initialized
|
||||
|
||||
return (tx_data_rd == 0 && tx_data_wr == 0 && rf_mode != TX_DATA_MODE && rf_mode != TX_STREAM_MODE && rf_mode != TX_CARRIER_MODE && rf_mode != TX_PN_MODE && rf_mode != RX_SCAN_SPECTRUM);
|
||||
}
|
||||
|
||||
// ************************************
|
||||
// set/get the frequency calibration value
|
||||
|
||||
void rfm22_setFreqCalibration(uint8_t value)
|
||||
{
|
||||
osc_load_cap = value;
|
||||
|
||||
if (!initialized || power_on_reset)
|
||||
return; // we haven't yet been initialized
|
||||
|
||||
uint8_t prev_rf_mode = rf_mode;
|
||||
|
||||
if (rf_mode == TX_CARRIER_MODE || rf_mode == TX_PN_MODE)
|
||||
{
|
||||
rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false);
|
||||
tx_data_rd = tx_data_wr = 0;
|
||||
}
|
||||
|
||||
#if defined(RFM22_EXT_INT_USE)
|
||||
exec_using_spi = TRUE;
|
||||
#endif
|
||||
|
||||
rfm22_write(RFM22_xtal_osc_load_cap, osc_load_cap);
|
||||
|
||||
#if defined(RFM22_EXT_INT_USE)
|
||||
exec_using_spi = FALSE;
|
||||
#endif
|
||||
|
||||
if (prev_rf_mode == TX_CARRIER_MODE || prev_rf_mode == TX_PN_MODE)
|
||||
rfm22_setTxMode(prev_rf_mode);
|
||||
}
|
||||
|
||||
uint8_t rfm22_getFreqCalibration(void)
|
||||
{
|
||||
return osc_load_cap;
|
||||
}
|
||||
|
||||
// ************************************
|
||||
// can be called from an interrupt if you wish
|
||||
|
||||
void rfm22_1ms_tick(void)
|
||||
{ // call this once every ms
|
||||
if (booting) return;
|
||||
if (!initialized) return; // we haven't yet been initialized
|
||||
|
||||
if (rf_mode != RX_SCAN_SPECTRUM)
|
||||
{
|
||||
if (rfm22_int_timer < 0xffff) rfm22_int_timer++;
|
||||
}
|
||||
}
|
||||
|
||||
// *****************************************************************************
|
||||
// call this as often as possible - not from an interrupt
|
||||
|
||||
void rfm22_process(void)
|
||||
{
|
||||
if (booting) return;
|
||||
if (!initialized) return; // we haven't yet been initialized
|
||||
|
||||
#if !defined(RFM22_EXT_INT_USE)
|
||||
if (rf_mode != RX_SCAN_SPECTRUM)
|
||||
rfm22_processInt(); // manually poll the interrupt line routine
|
||||
#endif
|
||||
|
||||
if (power_on_reset)
|
||||
{ // we need to re-initialize the RF module - it told us it's reset itself
|
||||
if (rf_mode != RX_SCAN_SPECTRUM)
|
||||
{ // normal data mode
|
||||
uint32_t current_freq = carrier_frequency_hz; // fetch current rf nominal frequency
|
||||
rfm22_init_normal(lower_carrier_frequency_limit_Hz, upper_carrier_frequency_limit_Hz, rfm22_freqHopSize());
|
||||
rfm22_setNominalCarrierFrequency(current_freq); // restore the nominal carrier frequency
|
||||
}
|
||||
else
|
||||
{ // we are scanning the spectrum
|
||||
rfm22_init_scan_spectrum(lower_carrier_frequency_limit_Hz, upper_carrier_frequency_limit_Hz);
|
||||
}
|
||||
return;
|
||||
}
|
||||
|
||||
switch (rf_mode)
|
||||
{
|
||||
case RX_SCAN_SPECTRUM: // we are scanning the spectrum
|
||||
|
||||
// read device status register
|
||||
device_status = rfm22_read(RFM22_device_status);
|
||||
|
||||
// read ezmac status register
|
||||
ezmac_status = rfm22_read(RFM22_ezmac_status);
|
||||
|
||||
// read interrupt status registers - clears the interrupt line
|
||||
int_status1 = rfm22_read(RFM22_interrupt_status1);
|
||||
int_status2 = rfm22_read(RFM22_interrupt_status2);
|
||||
|
||||
if (int_status2 & RFM22_is2_ipor)
|
||||
{ // the RF module has gone and done a reset - we need to re-initialize the rf module
|
||||
initialized = FALSE;
|
||||
power_on_reset = TRUE;
|
||||
return;
|
||||
}
|
||||
|
||||
break;
|
||||
|
||||
case RX_WAIT_PREAMBLE_MODE:
|
||||
|
||||
if (rfm22_int_timer >= timeout_ms)
|
||||
{ // assume somethings locked up
|
||||
rfm22_int_time_outs++;
|
||||
rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false); // reset the RF module to rx mode
|
||||
tx_data_rd = tx_data_wr = 0; // wipe TX buffer
|
||||
break;
|
||||
}
|
||||
|
||||
// go to transmit mode if we have data to send and the channel is clear to transmit on
|
||||
if (tx_data_rd == 0 && tx_data_wr > 0 && rfm22_channelIsClear())
|
||||
{
|
||||
rfm22_setTxMode(TX_DATA_MODE); // transmit packet NOW
|
||||
break;
|
||||
}
|
||||
|
||||
break;
|
||||
|
||||
case RX_WAIT_SYNC_MODE:
|
||||
|
||||
if (rfm22_int_timer >= timeout_sync_ms)
|
||||
{ // assume somethings locked up
|
||||
rfm22_int_time_outs++;
|
||||
rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false); // reset the RF module to rx mode
|
||||
tx_data_rd = tx_data_wr = 0; // wipe TX buffer
|
||||
break;
|
||||
}
|
||||
|
||||
// go to transmit mode if we have data to send and the channel is clear to transmit on
|
||||
if (tx_data_rd == 0 && tx_data_wr > 0 && rfm22_channelIsClear())
|
||||
{
|
||||
rfm22_setTxMode(TX_DATA_MODE); // transmit packet NOW
|
||||
break;
|
||||
}
|
||||
|
||||
break;
|
||||
|
||||
case RX_DATA_MODE:
|
||||
case TX_DATA_MODE:
|
||||
|
||||
if (rfm22_int_timer >= timeout_data_ms)
|
||||
{ // assume somethings locked up
|
||||
rfm22_int_time_outs++;
|
||||
rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false); // reset the RF module to rx mode
|
||||
tx_data_rd = tx_data_wr = 0; // wipe TX buffer
|
||||
break;
|
||||
}
|
||||
|
||||
break;
|
||||
|
||||
case TX_STREAM_MODE:
|
||||
|
||||
// todo:
|
||||
|
||||
break;
|
||||
|
||||
case TX_CARRIER_MODE:
|
||||
case TX_PN_MODE:
|
||||
|
||||
// if (rfm22_int_timer >= TX_TEST_MODE_TIMELIMIT_MS)
|
||||
// {
|
||||
// rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false); // back to rx mode
|
||||
// tx_data_rd = tx_data_wr = 0; // wipe TX buffer
|
||||
// break;
|
||||
// }
|
||||
|
||||
break;
|
||||
|
||||
default:
|
||||
// unknown mode - this should never happen, maybe we should do a complete CPU reset here?
|
||||
rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false); // to rx mode
|
||||
tx_data_rd = tx_data_wr = 0; // wipe TX buffer
|
||||
break;
|
||||
}
|
||||
|
||||
#if defined(RFM22_INT_TIMEOUT_DEBUG)
|
||||
if (prev_rfm22_int_time_outs != rfm22_int_time_outs)
|
||||
{
|
||||
prev_rfm22_int_time_outs = rfm22_int_time_outs;
|
||||
DEBUG_PRINTF("rf int timeouts %d\r\n", rfm22_int_time_outs);
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
// ************************************
|
||||
|
||||
void rfm22_TxDataByte_SetCallback(t_rfm22_TxDataByteCallback new_function)
|
||||
{
|
||||
tx_data_byte_callback_function = new_function;
|
||||
}
|
||||
|
||||
void rfm22_RxData_SetCallback(t_rfm22_RxDataCallback new_function)
|
||||
{
|
||||
rx_data_callback_function = new_function;
|
||||
}
|
||||
|
||||
// ************************************
|
||||
// reset the RF module
|
||||
|
||||
int rfm22_resetModule(uint8_t mode, uint32_t min_frequency_hz, uint32_t max_frequency_hz)
|
||||
{
|
||||
initialized = false;
|
||||
|
||||
#if defined(RFM22_EXT_INT_USE)
|
||||
rfm22_disableExtInt();
|
||||
#endif
|
||||
|
||||
power_on_reset = false;
|
||||
|
||||
// ****************
|
||||
|
||||
#if defined(RFM22_EXT_INT_USE)
|
||||
exec_using_spi = TRUE;
|
||||
#endif
|
||||
|
||||
// ****************
|
||||
// setup the SPI port
|
||||
|
||||
// chip select line HIGH
|
||||
PIOS_SPI_RC_PinSet(RFM22_PIOS_SPI, 1);
|
||||
|
||||
// set SPI port SCLK frequency .. 4.5MHz
|
||||
PIOS_SPI_SetClockSpeed(RFM22_PIOS_SPI, PIOS_SPI_PRESCALER_16);
|
||||
// set SPI port SCLK frequency .. 2.25MHz
|
||||
// PIOS_SPI_SetClockSpeed(RFM22_PIOS_SPI, PIOS_SPI_PRESCALER_32);
|
||||
|
||||
// set SPI port SCLK frequency .. 285kHz .. purely for hardware fault finding
|
||||
// PIOS_SPI_SetClockSpeed(RFM22_PIOS_SPI, PIOS_SPI_PRESCALER_256);
|
||||
|
||||
// ****************
|
||||
// software reset the RF chip .. following procedure according to Si4x3x Errata (rev. B)
|
||||
|
||||
rfm22_write(RFM22_op_and_func_ctrl1, RFM22_opfc1_swres); // software reset the radio
|
||||
|
||||
PIOS_DELAY_WaitmS(26); // wait 26ms
|
||||
|
||||
for (int i = 50; i > 0; i--)
|
||||
{
|
||||
PIOS_DELAY_WaitmS(1); // wait 1ms
|
||||
|
||||
// read the status registers
|
||||
int_status1 = rfm22_read(RFM22_interrupt_status1);
|
||||
int_status2 = rfm22_read(RFM22_interrupt_status2);
|
||||
if (int_status2 & RFM22_is2_ichiprdy) break;
|
||||
}
|
||||
|
||||
// ****************
|
||||
|
||||
// read status - clears interrupt
|
||||
device_status = rfm22_read(RFM22_device_status);
|
||||
int_status1 = rfm22_read(RFM22_interrupt_status1);
|
||||
int_status2 = rfm22_read(RFM22_interrupt_status2);
|
||||
ezmac_status = rfm22_read(RFM22_ezmac_status);
|
||||
|
||||
// disable all interrupts
|
||||
rfm22_write(RFM22_interrupt_enable1, 0x00);
|
||||
rfm22_write(RFM22_interrupt_enable2, 0x00);
|
||||
|
||||
// ****************
|
||||
|
||||
#if defined(RFM22_EXT_INT_USE)
|
||||
exec_using_spi = FALSE;
|
||||
#endif
|
||||
|
||||
// ****************
|
||||
|
||||
#if defined(RFM22_EXT_INT_USE)
|
||||
inside_ext_int = FALSE;
|
||||
#endif
|
||||
|
||||
rf_mode = mode;
|
||||
|
||||
device_status = int_status1 = int_status2 = ezmac_status = 0;
|
||||
|
||||
rssi = 0;
|
||||
rssi_dBm = -200;
|
||||
|
||||
tx_data_byte_callback_function = NULL;
|
||||
rx_data_callback_function = NULL;
|
||||
|
||||
rx_buffer_current = 0;
|
||||
rx_buffer_wr = 0;
|
||||
rx_packet_wr = 0;
|
||||
rx_packet_rssi_dBm = -200;
|
||||
rx_packet_afc_Hz = 0;
|
||||
|
||||
tx_data_addr = NULL;
|
||||
tx_data_rd = tx_data_wr = 0;
|
||||
|
||||
lookup_index = 0;
|
||||
ss_lookup_index = 0;
|
||||
|
||||
rf_bandwidth_used = 0;
|
||||
ss_rf_bandwidth_used = 0;
|
||||
|
||||
rfm22_int_timer = 0;
|
||||
rfm22_int_time_outs = 0;
|
||||
prev_rfm22_int_time_outs = 0;
|
||||
|
||||
hbsel = 0;
|
||||
frequency_step_size = 0.0f;
|
||||
|
||||
frequency_hop_channel = 0;
|
||||
|
||||
afc_correction = 0;
|
||||
afc_correction_Hz = 0;
|
||||
|
||||
temperature_reg = 0;
|
||||
|
||||
// set the TX power
|
||||
tx_power = RFM22_DEFAULT_RF_POWER;
|
||||
|
||||
tx_pwr = 0;
|
||||
|
||||
// ****************
|
||||
// read the RF chip ID bytes
|
||||
|
||||
device_type = rfm22_read(RFM22_DEVICE_TYPE) & RFM22_DT_MASK; // read the device type
|
||||
device_version = rfm22_read(RFM22_DEVICE_VERSION) & RFM22_DV_MASK; // read the device version
|
||||
|
||||
#if defined(RFM22_DEBUG)
|
||||
DEBUG_PRINTF("rf device type: %d\r\n", device_type);
|
||||
DEBUG_PRINTF("rf device version: %d\r\n", device_version);
|
||||
#endif
|
||||
|
||||
if (device_type != 0x08)
|
||||
{
|
||||
#if defined(RFM22_DEBUG)
|
||||
DEBUG_PRINTF("rf device type: INCORRECT - should be 0x08\r\n");
|
||||
#endif
|
||||
return -1; // incorrect RF module type
|
||||
}
|
||||
|
||||
// if (device_version != RFM22_DEVICE_VERSION_V2) // V2
|
||||
// return -2; // incorrect RF module version
|
||||
// if (device_version != RFM22_DEVICE_VERSION_A0) // A0
|
||||
// return -2; // incorrect RF module version
|
||||
if (device_version != RFM22_DEVICE_VERSION_B1) // B1
|
||||
{
|
||||
#if defined(RFM22_DEBUG)
|
||||
DEBUG_PRINTF("rf device version: INCORRECT\r\n");
|
||||
#endif
|
||||
return -2; // incorrect RF module version
|
||||
}
|
||||
|
||||
// ****************
|
||||
// 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;
|
||||
}
|
||||
|
||||
lower_carrier_frequency_limit_Hz = min_frequency_hz;
|
||||
upper_carrier_frequency_limit_Hz = max_frequency_hz;
|
||||
|
||||
// ****************
|
||||
// calibrate our RF module to be exactly on frequency .. different for every module
|
||||
|
||||
osc_load_cap = OSC_LOAD_CAP; // default
|
||||
rfm22_write(RFM22_xtal_osc_load_cap, osc_load_cap);
|
||||
|
||||
// ****************
|
||||
|
||||
// disable Low Duty Cycle Mode
|
||||
rfm22_write(RFM22_op_and_func_ctrl2, 0x00);
|
||||
|
||||
rfm22_write(RFM22_cpu_output_clk, RFM22_coc_1MHz); // 1MHz clock output
|
||||
|
||||
rfm22_write(RFM22_op_and_func_ctrl1, RFM22_opfc1_xton); // READY mode
|
||||
// rfm22_write(RFM22_op_and_func_ctrl1, RFM22_opfc1_pllon); // TUNE mode
|
||||
|
||||
// choose the 3 GPIO pin functions
|
||||
rfm22_write(RFM22_io_port_config, RFM22_io_port_default); // GPIO port use default value
|
||||
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(RFM22_gpio2_config, RFM22_gpio2_config_drv3 | RFM22_gpio2_config_cca); // GPIO2 = Clear Channel Assessment
|
||||
|
||||
// ****************
|
||||
|
||||
return 0; // OK
|
||||
}
|
||||
|
||||
// ************************************
|
||||
|
||||
int rfm22_init_scan_spectrum(uint32_t min_frequency_hz, uint32_t max_frequency_hz)
|
||||
{
|
||||
#if defined(RFM22_DEBUG)
|
||||
DEBUG_PRINTF("\r\nRF init scan spectrum\r\n");
|
||||
#endif
|
||||
|
||||
int res = rfm22_resetModule(RX_SCAN_SPECTRUM, min_frequency_hz, max_frequency_hz);
|
||||
if (res < 0)
|
||||
return res;
|
||||
|
||||
// rfm22_setSSBandwidth(0);
|
||||
rfm22_setSSBandwidth(1);
|
||||
|
||||
// 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);
|
||||
|
||||
rfm22_write(RFM22_cpu_output_clk, RFM22_coc_1MHz); // 1MHz clock output
|
||||
|
||||
rfm22_write(RFM22_rssi_threshold_clear_chan_indicator, 0);
|
||||
|
||||
rfm22_write(RFM22_preamble_detection_ctrl1, 31 << 3); // 31-nibbles rx preamble detection
|
||||
|
||||
// avoid packet detection
|
||||
rfm22_write(RFM22_data_access_control, RFM22_dac_enpacrx | RFM22_dac_encrc);
|
||||
rfm22_write(RFM22_header_control1, 0x0f);
|
||||
rfm22_write(RFM22_header_control2, 0x77);
|
||||
|
||||
rfm22_write(RFM22_sync_word3, SYNC_BYTE_1);
|
||||
rfm22_write(RFM22_sync_word2, SYNC_BYTE_2);
|
||||
rfm22_write(RFM22_sync_word1, SYNC_BYTE_3 ^ 0xff);
|
||||
rfm22_write(RFM22_sync_word0, SYNC_BYTE_4 ^ 0xff);
|
||||
|
||||
// all the bits to be checked
|
||||
rfm22_write(RFM22_header_enable3, 0xff);
|
||||
rfm22_write(RFM22_header_enable2, 0xff);
|
||||
rfm22_write(RFM22_header_enable1, 0xff);
|
||||
rfm22_write(RFM22_header_enable0, 0xff);
|
||||
|
||||
// rfm22_write(RFM22_frequency_hopping_step_size, 0); // set frequency hopping channel step size (multiples of 10kHz)
|
||||
|
||||
rfm22_setNominalCarrierFrequency(min_frequency_hz); // set our nominal carrier frequency
|
||||
|
||||
rfm22_write(RFM22_tx_power, RFM22_tx_pwr_lna_sw | 0); // set minimum tx power
|
||||
|
||||
rfm22_write(RFM22_agc_override1, RFM22_agc_ovr1_sgi | RFM22_agc_ovr1_agcen);
|
||||
|
||||
// rfm22_write(RFM22_vco_current_trimming, 0x7f);
|
||||
// rfm22_write(RFM22_vco_calibration_override, 0x40);
|
||||
// rfm22_write(RFM22_chargepump_current_trimming_override, 0x80);
|
||||
|
||||
#if defined(RFM22_EXT_INT_USE)
|
||||
// Enable RF module external interrupt
|
||||
rfm22_enableExtInt();
|
||||
#endif
|
||||
|
||||
rfm22_setRxMode(RX_SCAN_SPECTRUM, true);
|
||||
|
||||
initialized = true;
|
||||
|
||||
return 0; // OK
|
||||
}
|
||||
|
||||
// ************************************
|
||||
|
||||
int rfm22_init_tx_stream(uint32_t min_frequency_hz, uint32_t max_frequency_hz)
|
||||
{
|
||||
#if defined(RFM22_DEBUG)
|
||||
DEBUG_PRINTF("\r\nRF init TX stream\r\n");
|
||||
#endif
|
||||
|
||||
int res = rfm22_resetModule(TX_STREAM_MODE, min_frequency_hz, max_frequency_hz);
|
||||
if (res < 0)
|
||||
return res;
|
||||
|
||||
frequency_hop_step_size_reg = 0;
|
||||
|
||||
// set the RF datarate
|
||||
rfm22_setDatarate(RFM22_DEFAULT_RF_DATARATE, FALSE);
|
||||
|
||||
// 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);
|
||||
|
||||
// disable the internal Tx & Rx packet handlers (without CRC)
|
||||
rfm22_write(RFM22_data_access_control, 0);
|
||||
|
||||
rfm22_write(RFM22_preamble_length, TX_PREAMBLE_NIBBLES); // x-nibbles tx preamble
|
||||
rfm22_write(RFM22_preamble_detection_ctrl1, RX_PREAMBLE_NIBBLES << 3); // x-nibbles rx preamble detection
|
||||
|
||||
rfm22_write(RFM22_header_control1, RFM22_header_cntl1_bcen_none | RFM22_header_cntl1_hdch_none); // header control - we are not using the header
|
||||
rfm22_write(RFM22_header_control2, RFM22_header_cntl2_fixpklen | RFM22_header_cntl2_hdlen_none | RFM22_header_cntl2_synclen_32 | ((TX_PREAMBLE_NIBBLES >> 8) & 0x01)); // no header bytes, synchronization word length 3, 2 used, packet length not included in header (fixed packet length).
|
||||
|
||||
rfm22_write(RFM22_sync_word3, SYNC_BYTE_1); // sync word
|
||||
rfm22_write(RFM22_sync_word2, SYNC_BYTE_2); //
|
||||
|
||||
// rfm22_write(RFM22_modem_test, 0x01);
|
||||
|
||||
rfm22_write(RFM22_agc_override1, RFM22_agc_ovr1_agcen);
|
||||
// rfm22_write(RFM22_agc_override1, RFM22_agc_ovr1_sgi | RFM22_agc_ovr1_agcen);
|
||||
|
||||
rfm22_write(RFM22_frequency_hopping_step_size, frequency_hop_step_size_reg); // set frequency hopping channel step size (multiples of 10kHz)
|
||||
|
||||
rfm22_setNominalCarrierFrequency((min_frequency_hz + max_frequency_hz) / 2); // set our nominal carrier frequency
|
||||
|
||||
rfm22_write(RFM22_tx_power, RFM22_tx_pwr_papeaken | RFM22_tx_pwr_papeaklvl_0 | RFM22_tx_pwr_lna_sw | tx_power); // set the tx power
|
||||
// rfm22_write(RFM22_tx_power, RFM22_tx_pwr_lna_sw | tx_power); // set the tx power
|
||||
|
||||
// rfm22_write(RFM22_vco_current_trimming, 0x7f);
|
||||
// rfm22_write(RFM22_vco_calibration_override, 0x40);
|
||||
// rfm22_write(RFM22_chargepump_current_trimming_override, 0x80);
|
||||
|
||||
rfm22_write(RFM22_tx_fifo_control1, TX_FIFO_HI_WATERMARK); // TX FIFO Almost Full Threshold (0 - 63)
|
||||
rfm22_write(RFM22_tx_fifo_control2, TX_FIFO_LO_WATERMARK); // TX FIFO Almost Empty Threshold (0 - 63)
|
||||
|
||||
#if defined(RFM22_EXT_INT_USE)
|
||||
// Enable RF module external interrupt
|
||||
rfm22_enableExtInt();
|
||||
#endif
|
||||
|
||||
initialized = true;
|
||||
|
||||
return 0; // OK
|
||||
}
|
||||
|
||||
// ************************************
|
||||
|
||||
int rfm22_init_rx_stream(uint32_t min_frequency_hz, uint32_t max_frequency_hz)
|
||||
{
|
||||
#if defined(RFM22_DEBUG)
|
||||
DEBUG_PRINTF("\r\nRF init RX stream\r\n");
|
||||
#endif
|
||||
|
||||
int res = rfm22_resetModule(RX_WAIT_PREAMBLE_MODE, min_frequency_hz, max_frequency_hz);
|
||||
if (res < 0)
|
||||
return res;
|
||||
|
||||
frequency_hop_step_size_reg = 0;
|
||||
|
||||
// set the RF datarate
|
||||
rfm22_setDatarate(RFM22_DEFAULT_RF_DATARATE, FALSE);
|
||||
|
||||
// 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);
|
||||
|
||||
// disable the internal Tx & Rx packet handlers (without CRC)
|
||||
rfm22_write(RFM22_data_access_control, 0);
|
||||
|
||||
rfm22_write(RFM22_preamble_length, TX_PREAMBLE_NIBBLES); // x-nibbles tx preamble
|
||||
rfm22_write(RFM22_preamble_detection_ctrl1, RX_PREAMBLE_NIBBLES << 3); // x-nibbles rx preamble detection
|
||||
|
||||
rfm22_write(RFM22_header_control1, RFM22_header_cntl1_bcen_none | RFM22_header_cntl1_hdch_none); // header control - we are not using the header
|
||||
rfm22_write(RFM22_header_control2, RFM22_header_cntl2_fixpklen | RFM22_header_cntl2_hdlen_none | RFM22_header_cntl2_synclen_32 | ((TX_PREAMBLE_NIBBLES >> 8) & 0x01)); // no header bytes, synchronization word length 3, 2 used, packet length not included in header (fixed packet length).
|
||||
|
||||
rfm22_write(RFM22_sync_word3, SYNC_BYTE_1); // sync word
|
||||
rfm22_write(RFM22_sync_word2, SYNC_BYTE_2); //
|
||||
|
||||
// no header bits to be checked
|
||||
rfm22_write(RFM22_header_enable3, 0x00);
|
||||
rfm22_write(RFM22_header_enable2, 0x00);
|
||||
rfm22_write(RFM22_header_enable1, 0x00);
|
||||
rfm22_write(RFM22_header_enable0, 0x00);
|
||||
|
||||
// rfm22_write(RFM22_modem_test, 0x01);
|
||||
|
||||
rfm22_write(RFM22_agc_override1, RFM22_agc_ovr1_agcen);
|
||||
// rfm22_write(RFM22_agc_override1, RFM22_agc_ovr1_sgi | RFM22_agc_ovr1_agcen);
|
||||
|
||||
rfm22_write(RFM22_frequency_hopping_step_size, frequency_hop_step_size_reg); // set frequency hopping channel step size (multiples of 10kHz)
|
||||
|
||||
rfm22_setNominalCarrierFrequency((min_frequency_hz + max_frequency_hz) / 2); // set our nominal carrier frequency
|
||||
|
||||
// rfm22_write(RFM22_vco_current_trimming, 0x7f);
|
||||
// rfm22_write(RFM22_vco_calibration_override, 0x40);
|
||||
// rfm22_write(RFM22_chargepump_current_trimming_override, 0x80);
|
||||
|
||||
rfm22_write(RFM22_rx_fifo_control, RX_FIFO_HI_WATERMARK); // RX FIFO Almost Full Threshold (0 - 63)
|
||||
|
||||
#if defined(RFM22_EXT_INT_USE)
|
||||
// Enable RF module external interrupt
|
||||
rfm22_enableExtInt();
|
||||
#endif
|
||||
|
||||
rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false);
|
||||
|
||||
initialized = true;
|
||||
|
||||
return 0; // OK
|
||||
}
|
||||
|
||||
// ************************************
|
||||
// Initialise this hardware layer module and the rf module
|
||||
|
||||
int rfm22_init_normal(uint32_t min_frequency_hz, uint32_t max_frequency_hz, uint32_t freq_hop_step_size)
|
||||
{
|
||||
#if defined(RFM22_DEBUG)
|
||||
DEBUG_PRINTF("\r\nRF init normal\r\n");
|
||||
#endif
|
||||
|
||||
int res = rfm22_resetModule(RX_WAIT_PREAMBLE_MODE, min_frequency_hz, max_frequency_hz);
|
||||
if (res < 0)
|
||||
return res;
|
||||
|
||||
// ****************
|
||||
|
||||
freq_hop_step_size /= 10000; // in 10kHz increments
|
||||
if (freq_hop_step_size > 255) freq_hop_step_size = 255;
|
||||
|
||||
frequency_hop_step_size_reg = freq_hop_step_size;
|
||||
|
||||
// ****************
|
||||
|
||||
// set the RF datarate
|
||||
rfm22_setDatarate(RFM22_DEFAULT_RF_DATARATE, TRUE);
|
||||
|
||||
// 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);
|
||||
|
||||
// setup to read the internal temperature sensor
|
||||
adc_config = RFM22_ac_adcsel_temp_sensor | RFM22_ac_adcref_bg; // ADC used to sample the temperature sensor
|
||||
rfm22_write(RFM22_adc_config, adc_config); //
|
||||
rfm22_write(RFM22_adc_sensor_amp_offset, 0); // adc offset
|
||||
rfm22_write(RFM22_temp_sensor_calib, RFM22_tsc_tsrange0 | RFM22_tsc_entsoffs); // temp sensor calibration .. –40C to +64C 0.5C resolution
|
||||
rfm22_write(RFM22_temp_value_offset, 0); // temp sensor offset
|
||||
rfm22_write(RFM22_adc_config, adc_config | RFM22_ac_adcstartbusy); // start an ADC conversion
|
||||
|
||||
rfm22_write(RFM22_rssi_threshold_clear_chan_indicator, (-90 + 122) * 2); // set the RSSI threshold interrupt to about -90dBm
|
||||
|
||||
// enable the internal Tx & Rx packet handlers (with CRC)
|
||||
// rfm22_write(RFM22_data_access_control, RFM22_dac_enpacrx | RFM22_dac_enpactx | RFM22_dac_encrc | RFM22_dac_crc_crc16);
|
||||
// enable the internal Tx & Rx packet handlers (without CRC)
|
||||
rfm22_write(RFM22_data_access_control, RFM22_dac_enpacrx | RFM22_dac_enpactx);
|
||||
|
||||
rfm22_write(RFM22_preamble_length, TX_PREAMBLE_NIBBLES); // x-nibbles tx preamble
|
||||
rfm22_write(RFM22_preamble_detection_ctrl1, RX_PREAMBLE_NIBBLES << 3); // x-nibbles rx preamble detection
|
||||
|
||||
rfm22_write(RFM22_header_control1, RFM22_header_cntl1_bcen_none | RFM22_header_cntl1_hdch_none); // header control - we are not using the header
|
||||
rfm22_write(RFM22_header_control2, RFM22_header_cntl2_hdlen_none | RFM22_header_cntl2_synclen_3210 | ((TX_PREAMBLE_NIBBLES >> 8) & 0x01)); // no header bytes, synchronization word length 3, 2, 1 & 0 used, packet length included in header.
|
||||
|
||||
rfm22_write(RFM22_sync_word3, SYNC_BYTE_1); // sync word
|
||||
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(RFM22_transmit_header3, 'p'); // set tx header
|
||||
rfm22_write(RFM22_transmit_header2, 'i'); //
|
||||
rfm22_write(RFM22_transmit_header1, 'p'); //
|
||||
rfm22_write(RFM22_transmit_header0, ' '); //
|
||||
|
||||
rfm22_write(RFM22_check_header3, 'p'); // set expected rx header
|
||||
rfm22_write(RFM22_check_header2, 'i'); //
|
||||
rfm22_write(RFM22_check_header1, 'p'); //
|
||||
rfm22_write(RFM22_check_header0, ' '); //
|
||||
|
||||
// all the bits to be checked
|
||||
rfm22_write(RFM22_header_enable3, 0xff);
|
||||
rfm22_write(RFM22_header_enable2, 0xff);
|
||||
rfm22_write(RFM22_header_enable1, 0xff);
|
||||
rfm22_write(RFM22_header_enable0, 0xff);
|
||||
*/ // no bits to be checked
|
||||
rfm22_write(RFM22_header_enable3, 0x00);
|
||||
rfm22_write(RFM22_header_enable2, 0x00);
|
||||
rfm22_write(RFM22_header_enable1, 0x00);
|
||||
rfm22_write(RFM22_header_enable0, 0x00);
|
||||
|
||||
// rfm22_write(RFM22_modem_test, 0x01);
|
||||
|
||||
rfm22_write(RFM22_agc_override1, RFM22_agc_ovr1_agcen);
|
||||
// rfm22_write(RFM22_agc_override1, RFM22_agc_ovr1_sgi | RFM22_agc_ovr1_agcen);
|
||||
|
||||
rfm22_write(RFM22_frequency_hopping_step_size, frequency_hop_step_size_reg); // set frequency hopping channel step size (multiples of 10kHz)
|
||||
|
||||
rfm22_setNominalCarrierFrequency((min_frequency_hz + max_frequency_hz) / 2); // set our nominal carrier frequency
|
||||
|
||||
rfm22_write(RFM22_tx_power, RFM22_tx_pwr_papeaken | RFM22_tx_pwr_papeaklvl_0 | RFM22_tx_pwr_lna_sw | tx_power); // set the tx power
|
||||
// rfm22_write(RFM22_tx_power, RFM22_tx_pwr_lna_sw | tx_power); // set the tx power
|
||||
|
||||
// rfm22_write(RFM22_vco_current_trimming, 0x7f);
|
||||
// rfm22_write(RFM22_vco_calibration_override, 0x40);
|
||||
// rfm22_write(RFM22_chargepump_current_trimming_override, 0x80);
|
||||
|
||||
rfm22_write(RFM22_tx_fifo_control1, TX_FIFO_HI_WATERMARK); // TX FIFO Almost Full Threshold (0 - 63)
|
||||
rfm22_write(RFM22_tx_fifo_control2, TX_FIFO_LO_WATERMARK); // TX FIFO Almost Empty Threshold (0 - 63)
|
||||
|
||||
rfm22_write(RFM22_rx_fifo_control, RX_FIFO_HI_WATERMARK); // RX FIFO Almost Full Threshold (0 - 63)
|
||||
|
||||
#if defined(RFM22_EXT_INT_USE)
|
||||
// Enable RF module external interrupt
|
||||
rfm22_enableExtInt();
|
||||
#endif
|
||||
|
||||
rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false);
|
||||
|
||||
initialized = true;
|
||||
|
||||
return 0; // ok
|
||||
}
|
||||
|
||||
// ************************************
|
@ -1,326 +0,0 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file saved_settings.c
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @brief RF Module hardware layer
|
||||
* @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 <string.h> // memmove, memset
|
||||
|
||||
#include "crc.h"
|
||||
#include "gpio_in.h"
|
||||
#include "saved_settings.h"
|
||||
#include "main.h"
|
||||
|
||||
#if defined(PIOS_COM_DEBUG)
|
||||
#define SAVED_SETTINGS_DEBUG
|
||||
#endif
|
||||
|
||||
// *****************************************************************
|
||||
|
||||
// default aes 128-bit encryption key
|
||||
const uint8_t saved_settings_default_aes_key[16] = {0x65, 0x3b, 0x71, 0x89, 0x4a, 0xf4, 0xc8, 0xcb, 0x18, 0xd4, 0x9b, 0x4d, 0x4a, 0xbe, 0xc8, 0x37};
|
||||
|
||||
// *****************************************************************
|
||||
|
||||
#define pages 1 // number of flash pages to use
|
||||
|
||||
uint32_t eeprom_addr; // the address of the emulated EEPROM area in program flash area
|
||||
uint16_t eeprom_page_size; // flash page size
|
||||
|
||||
volatile t_saved_settings saved_settings __attribute__ ((aligned(4))); // a RAM copy of the settings stored in EEPROM
|
||||
t_saved_settings tmp_settings __attribute__ ((aligned(4)));
|
||||
|
||||
// *****************************************************************
|
||||
// Private functions
|
||||
|
||||
bool saved_settings_page_empty(int page)
|
||||
{ // return TRUE if the flash page is emtpy (erased), otherwise return FALSE
|
||||
|
||||
if (page < 0 || page >= pages)
|
||||
return FALSE;
|
||||
|
||||
__IO uint32_t *addr = (__IO uint32_t *)(eeprom_addr + eeprom_page_size * page);
|
||||
int32_t len = eeprom_page_size / 4;
|
||||
|
||||
for (int32_t i = len; i > 0; i--)
|
||||
if (*addr++ != 0xffffffff)
|
||||
return FALSE; // the page is not erased
|
||||
|
||||
return TRUE;
|
||||
}
|
||||
|
||||
bool saved_settings_settings_empty(uint32_t addr)
|
||||
{ // return TRUE if the settings flash area is emtpy (erased), otherwise return FALSE
|
||||
|
||||
__IO uint8_t *p = (__IO uint8_t *)addr;
|
||||
|
||||
for (int32_t i = sizeof(t_saved_settings); i > 0; i--)
|
||||
if (*p++ != 0xff)
|
||||
return FALSE; // the flash area is not empty/erased
|
||||
|
||||
return TRUE;
|
||||
}
|
||||
|
||||
// *****************************************************************
|
||||
|
||||
int32_t saved_settings_read(void)
|
||||
{ // look for the last valid settings saved in EEPROM
|
||||
|
||||
uint32_t flash_addr;
|
||||
__IO uint8_t *p1;
|
||||
uint8_t *p2;
|
||||
|
||||
flash_addr = eeprom_addr;
|
||||
|
||||
if (saved_settings_settings_empty(flash_addr))
|
||||
{
|
||||
#if defined(SAVED_SETTINGS_DEBUG)
|
||||
DEBUG_PRINTF("settings Read, no settings found at %08X\r\n", flash_addr);
|
||||
#endif
|
||||
|
||||
return -1; // no settings found at the specified addr
|
||||
}
|
||||
|
||||
// copy the data from program flash area into temp settings area
|
||||
p1 = (__IO uint8_t *)flash_addr;
|
||||
p2 = (uint8_t *)&tmp_settings;
|
||||
for (int32_t i = 0; i < sizeof(t_saved_settings); i++)
|
||||
*p2++ = *p1++;
|
||||
|
||||
// calculate and check the CRC
|
||||
uint32_t crc1 = tmp_settings.crc;
|
||||
tmp_settings.crc = 0;
|
||||
uint32_t crc2 = updateCRC32Data(0xffffffff, (void *)&tmp_settings, sizeof(t_saved_settings));
|
||||
if (crc2 != crc1)
|
||||
{
|
||||
#if defined(SAVED_SETTINGS_DEBUG)
|
||||
DEBUG_PRINTF("settings Read crc error: %08X %08X\r\n", crc1, crc2);
|
||||
#endif
|
||||
|
||||
return -2; // error
|
||||
}
|
||||
|
||||
memmove((void *)&saved_settings, (void *)&tmp_settings, sizeof(t_saved_settings));
|
||||
|
||||
#if defined(SAVED_SETTINGS_DEBUG)
|
||||
DEBUG_PRINTF("settings Read OK!\r\n");
|
||||
#endif
|
||||
|
||||
return 0; // OK
|
||||
}
|
||||
|
||||
// *****************************************************************
|
||||
// Public functions
|
||||
|
||||
int32_t saved_settings_save(void)
|
||||
{ // save the settings into EEPROM
|
||||
|
||||
FLASH_Status fs;
|
||||
uint32_t flash_addr;
|
||||
uint8_t *p1;
|
||||
__IO uint8_t *p2;
|
||||
uint32_t *p3;
|
||||
bool do_save;
|
||||
|
||||
// size of the settings aligned to 4 bytes
|
||||
// uint16_t settings_size = (uint16_t)(sizeof(t_saved_settings) + 3) & 0xfffc;
|
||||
|
||||
// address of settings in FLASH area
|
||||
flash_addr = eeprom_addr;
|
||||
|
||||
// *****************************************
|
||||
// calculate and add the CRC
|
||||
|
||||
saved_settings.crc = 0;
|
||||
saved_settings.crc = updateCRC32Data(0xffffffff, (void *)&saved_settings, sizeof(t_saved_settings));
|
||||
|
||||
// *****************************************
|
||||
// first check to see if we need to save the settings
|
||||
|
||||
p1 = (uint8_t *)&saved_settings;
|
||||
p2 = (__IO uint8_t *)flash_addr;
|
||||
do_save = FALSE;
|
||||
|
||||
for (int32_t i = 0; i < sizeof(t_saved_settings); i++)
|
||||
{
|
||||
if (*p1++ != *p2++)
|
||||
{ // we need to save the settings
|
||||
do_save = TRUE;
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
if (!do_save)
|
||||
{
|
||||
#if defined(SAVED_SETTINGS_DEBUG)
|
||||
DEBUG_PRINTF("settings already saved OK\r\n");
|
||||
#endif
|
||||
|
||||
return 0; // settings already saved .. all OK
|
||||
}
|
||||
|
||||
// *****************************************
|
||||
|
||||
// Unlock the Flash Program Erase controller
|
||||
FLASH_Unlock();
|
||||
|
||||
if (!saved_settings_page_empty(0))
|
||||
{ // erase the page
|
||||
#if defined(SAVED_SETTINGS_DEBUG)
|
||||
DEBUG_PRINTF("settings erasing page .. ");
|
||||
#endif
|
||||
|
||||
fs = FLASH_ErasePage(eeprom_addr);
|
||||
if (fs != FLASH_COMPLETE)
|
||||
{ // error
|
||||
FLASH_Lock();
|
||||
|
||||
#if defined(SAVED_SETTINGS_DEBUG)
|
||||
DEBUG_PRINTF("error %d\r\n", fs);
|
||||
#endif
|
||||
|
||||
return -1;
|
||||
}
|
||||
|
||||
#if defined(SAVED_SETTINGS_DEBUG)
|
||||
DEBUG_PRINTF("OK\r\n");
|
||||
#endif
|
||||
}
|
||||
else
|
||||
{
|
||||
#if defined(SAVED_SETTINGS_DEBUG)
|
||||
DEBUG_PRINTF("settings page already erased\r\n");
|
||||
#endif
|
||||
}
|
||||
|
||||
// *****************************************
|
||||
// save the settings into flash area (emulated EEPROM area)
|
||||
|
||||
p1 = (uint8_t *)&saved_settings;
|
||||
p3 = (uint32_t *)flash_addr;
|
||||
|
||||
// write 4 bytes at a time into program flash area (emulated EEPROM area)
|
||||
for (int32_t i = 0; i < sizeof(t_saved_settings); p3++)
|
||||
{
|
||||
uint32_t value = 0;
|
||||
if (i < sizeof(t_saved_settings)) value |= (uint32_t)*p1++ << 0; else value |= 0x000000ff; i++;
|
||||
if (i < sizeof(t_saved_settings)) value |= (uint32_t)*p1++ << 8; else value |= 0x0000ff00; i++;
|
||||
if (i < sizeof(t_saved_settings)) value |= (uint32_t)*p1++ << 16; else value |= 0x00ff0000; i++;
|
||||
if (i < sizeof(t_saved_settings)) value |= (uint32_t)*p1++ << 24; else value |= 0xff000000; i++;
|
||||
|
||||
fs = FLASH_ProgramWord((uint32_t)p3, value); // write a 32-bit value
|
||||
if (fs != FLASH_COMPLETE)
|
||||
{
|
||||
FLASH_Lock();
|
||||
|
||||
#if defined(SAVED_SETTINGS_DEBUG)
|
||||
DEBUG_PRINTF("settings FLASH_ProgramWord error: %d\r\n", fs);
|
||||
#endif
|
||||
|
||||
return -2; // error
|
||||
}
|
||||
}
|
||||
|
||||
// Lock the Flash Program Erase controller
|
||||
FLASH_Lock();
|
||||
|
||||
// *****************************************
|
||||
// now error check it by reading it back (simple compare)
|
||||
|
||||
p1 = (uint8_t *)&saved_settings;
|
||||
p2 = (__IO uint8_t *)flash_addr;
|
||||
|
||||
for (int32_t i = 0; i < sizeof(t_saved_settings); i++)
|
||||
{
|
||||
if (*p1++ != *p2++)
|
||||
{
|
||||
#if defined(SAVED_SETTINGS_DEBUG)
|
||||
DEBUG_PRINTF("settings WriteSettings compare error\r\n");
|
||||
#endif
|
||||
|
||||
return -3; // error
|
||||
}
|
||||
}
|
||||
|
||||
// *****************************************
|
||||
|
||||
#if defined(SAVED_SETTINGS_DEBUG)
|
||||
DEBUG_PRINTF("settings Save OK!\r\n");
|
||||
#endif
|
||||
|
||||
return 0; // OK
|
||||
}
|
||||
|
||||
void saved_settings_init(void)
|
||||
{
|
||||
// **********
|
||||
// determine emulated EEPROM details
|
||||
|
||||
if (flash_size < 256000)
|
||||
eeprom_page_size = 1024; // 1 kByte
|
||||
else
|
||||
eeprom_page_size = 2048; // 2 kByte
|
||||
|
||||
// place emulated eeprom at end of program flash area
|
||||
eeprom_addr = (0x08000000 + flash_size) - (eeprom_page_size * pages);
|
||||
|
||||
#if defined(SAVED_SETTINGS_DEBUG)
|
||||
DEBUG_PRINTF("\r\n");
|
||||
DEBUG_PRINTF("settings eeprom addr: %08x\r\n", eeprom_addr);
|
||||
DEBUG_PRINTF("settings eeprom page size: %u\r\n", eeprom_page_size);
|
||||
DEBUG_PRINTF("settings eeprom pages: %u\r\n", pages);
|
||||
#endif
|
||||
|
||||
// **********
|
||||
// default settings
|
||||
|
||||
memset((void *)&saved_settings, 0xff, sizeof(t_saved_settings));
|
||||
|
||||
saved_settings.mode = MODE_NORMAL;
|
||||
|
||||
saved_settings.destination_id = 0;
|
||||
|
||||
saved_settings.frequency_band = FREQBAND_UNKNOWN;
|
||||
|
||||
saved_settings.rf_xtal_cap = 0x7f;
|
||||
|
||||
saved_settings.aes_enable = FALSE;
|
||||
memmove((void *)&saved_settings.aes_key, saved_settings_default_aes_key, sizeof(saved_settings.aes_key));
|
||||
|
||||
saved_settings.serial_baudrate = 57600;
|
||||
|
||||
saved_settings.rts_time = 10; // ms
|
||||
|
||||
// saved_settings.crc = 0;
|
||||
// saved_settings.crc = updateCRC32Data(0xffffffff, (void *)&saved_settings, sizeof(t_saved_settings));
|
||||
|
||||
// **********
|
||||
|
||||
// Lock the Flash Program Erase controller
|
||||
FLASH_Lock();
|
||||
|
||||
saved_settings_read();
|
||||
|
||||
// **********
|
||||
}
|
||||
|
||||
// *****************************************************************
|
@ -1,156 +0,0 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file stopwatch.c
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @brief Stop watch function
|
||||
* @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 "stopwatch.h"
|
||||
#include "main.h"
|
||||
|
||||
// *****************************************************************************
|
||||
|
||||
uint32_t resolution_us = 0;
|
||||
|
||||
// *****************************************************************************
|
||||
// initialise the stopwatch
|
||||
|
||||
void STOPWATCH_init(uint32_t resolution)
|
||||
{
|
||||
resolution_us = resolution;
|
||||
|
||||
if (resolution_us == 0)
|
||||
return;
|
||||
|
||||
// enable timer clock
|
||||
switch ((uint32_t)STOPWATCH_TIMER)
|
||||
{
|
||||
case (uint32_t)TIM1: RCC_APB2PeriphClockCmd(RCC_APB2Periph_TIM1, ENABLE); break;
|
||||
case (uint32_t)TIM2: RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM2, ENABLE); break;
|
||||
case (uint32_t)TIM3: RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM3, ENABLE); break;
|
||||
case (uint32_t)TIM4: RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM4, ENABLE); break;
|
||||
#ifdef STM32F10X_HD
|
||||
case (uint32_t)TIM5: RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM5, ENABLE); break;
|
||||
case (uint32_t)TIM6: RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM6, ENABLE); break;
|
||||
case (uint32_t)TIM7: RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM7, ENABLE); break;
|
||||
case (uint32_t)TIM8: RCC_APB2PeriphClockCmd(RCC_APB2Periph_TIM8, ENABLE); break;
|
||||
#endif
|
||||
}
|
||||
|
||||
// time base configuration
|
||||
TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure;
|
||||
TIM_TimeBaseStructure.TIM_Period = 0xffff; // max period
|
||||
TIM_TimeBaseStructure.TIM_Prescaler = ((PIOS_MASTER_CLOCK / 1000000) * resolution_us) - 1; // <resolution> uS accuracy @ 72 MHz
|
||||
TIM_TimeBaseStructure.TIM_ClockDivision = 0;
|
||||
TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up;
|
||||
TIM_TimeBaseInit(STOPWATCH_TIMER, &TIM_TimeBaseStructure);
|
||||
|
||||
// enable interrupt request
|
||||
TIM_ITConfig(STOPWATCH_TIMER, TIM_IT_Update, ENABLE);
|
||||
|
||||
// start counter
|
||||
TIM_Cmd(STOPWATCH_TIMER, ENABLE);
|
||||
}
|
||||
|
||||
// *****************************************************************************
|
||||
// timer interrupt
|
||||
/*
|
||||
#ifdef STM32F10X_MD
|
||||
#if (STOPWATCH_TIMER == TIM1)
|
||||
void TIM1_IRQHandler(void)
|
||||
#if (STOPWATCH_TIMER == TIM2)
|
||||
void TIM2_IRQHandler(void)
|
||||
#elif (STOPWATCH_TIMER == TIM3)
|
||||
void TIM3_IRQHandler(void)
|
||||
#elif (STOPWATCH_TIMER == TIM4)
|
||||
void TIM4_IRQHandler(void)
|
||||
#endif
|
||||
#endif
|
||||
#ifdef STM32F10X_HD
|
||||
#if (STOPWATCH_TIMER == TIM1)
|
||||
void TIM1_IRQHandler(void)
|
||||
#if (STOPWATCH_TIMER == TIM2)
|
||||
void TIM2_IRQHandler(void)
|
||||
#elif (STOPWATCH_TIMER == TIM3)
|
||||
void TIM3_IRQHandler(void)
|
||||
#elif (STOPWATCH_TIMER == TIM4)
|
||||
void TIM4_IRQHandler(void)
|
||||
#elif (STOPWATCH_TIMER == TIM5)
|
||||
void TIM5_IRQHandler(void)
|
||||
#elif (STOPWATCH_TIMER == TIM6)
|
||||
void TIM6_IRQHandler(void)
|
||||
#elif (STOPWATCH_TIMER == TIM7)
|
||||
void TIM7_IRQHandler(void)
|
||||
#elif (STOPWATCH_TIMER == TIM8)
|
||||
void TIM8_IRQHandler(void)
|
||||
#endif
|
||||
#endif
|
||||
{
|
||||
|
||||
}
|
||||
*/
|
||||
// *****************************************************************************
|
||||
// resets the stopwatch
|
||||
|
||||
void STOPWATCH_reset(void)
|
||||
{
|
||||
if (resolution_us > 0)
|
||||
{ // reset the counter
|
||||
STOPWATCH_TIMER->CNT = 1; // set to 1 instead of 0 to avoid new IRQ request
|
||||
TIM_ClearITPendingBit(STOPWATCH_TIMER, TIM_IT_Update);
|
||||
}
|
||||
}
|
||||
|
||||
// *****************************************************************************
|
||||
// returns the timer count since the last STOPWATCH_reset() call
|
||||
// return 0xffffffff if counter overrun or not initialised
|
||||
|
||||
uint32_t STOPWATCH_get_count(void)
|
||||
{
|
||||
uint32_t value = STOPWATCH_TIMER->CNT; // get counter value ASAP
|
||||
|
||||
if (resolution_us == 0)
|
||||
return 0xffffffff; // not initialized
|
||||
|
||||
if (TIM_GetITStatus(STOPWATCH_TIMER, TIM_IT_Update) != RESET)
|
||||
return 0xffffffff; // timer overfloaw
|
||||
|
||||
return value; // return the timer count
|
||||
}
|
||||
|
||||
// *****************************************************************************
|
||||
// returns number of us since the last STOPWATCH_reset() call
|
||||
// return 0xffffffff if counter overrun or not initialised
|
||||
|
||||
uint32_t STOPWATCH_get_us(void)
|
||||
{
|
||||
uint32_t value = STOPWATCH_TIMER->CNT; // get counter value ASAP
|
||||
|
||||
if (resolution_us == 0)
|
||||
return 0xffffffff; // not initialized
|
||||
|
||||
if (TIM_GetITStatus(STOPWATCH_TIMER, TIM_IT_Update) != RESET)
|
||||
return 0xffffffff; // timer overfloaw
|
||||
|
||||
return (value * resolution_us); // return number of micro seconds
|
||||
}
|
||||
|
||||
// *****************************************************************************
|
@ -1,122 +0,0 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file stream.c
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @brief Sends or Receives a continuous packet stream to/from the remote unit
|
||||
* @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 <string.h> // memmove
|
||||
|
||||
#include "main.h"
|
||||
#include "rfm22b.h"
|
||||
#include "fifo_buffer.h"
|
||||
#include "aes.h"
|
||||
#include "crc.h"
|
||||
#include "saved_settings.h"
|
||||
#include "stream.h"
|
||||
|
||||
#if defined(PIOS_COM_DEBUG)
|
||||
#define STREAM_DEBUG
|
||||
#endif
|
||||
|
||||
// *************************************************************
|
||||
// can be called from an interrupt if you wish
|
||||
// call this once every ms
|
||||
|
||||
void stream_1ms_tick(void)
|
||||
{
|
||||
if (booting) return;
|
||||
|
||||
if (saved_settings.mode == MODE_STREAM_TX)
|
||||
{
|
||||
}
|
||||
else
|
||||
if (saved_settings.mode == MODE_STREAM_RX)
|
||||
{
|
||||
}
|
||||
}
|
||||
|
||||
// *************************************************************
|
||||
// return a byte for the tx packet transmission.
|
||||
//
|
||||
// return value < 0 if no more bytes available, otherwise return byte to be sent
|
||||
|
||||
int16_t stream_TxDataByteCallback(void)
|
||||
{
|
||||
return -1;
|
||||
}
|
||||
|
||||
// *************************************************************
|
||||
// we are being given a block of received bytes
|
||||
//
|
||||
// return TRUE to continue current packet receive, otherwise return FALSE to halt current packet reception
|
||||
|
||||
bool stream_RxDataCallback(void *data, uint8_t len)
|
||||
{
|
||||
return true;
|
||||
}
|
||||
|
||||
// *************************************************************
|
||||
// call this from the main loop (not interrupt) as often as possible
|
||||
|
||||
void stream_process(void)
|
||||
{
|
||||
if (booting) return;
|
||||
|
||||
if (saved_settings.mode == MODE_STREAM_TX)
|
||||
{
|
||||
}
|
||||
else
|
||||
if (saved_settings.mode == MODE_STREAM_RX)
|
||||
{
|
||||
}
|
||||
}
|
||||
|
||||
// *************************************************************
|
||||
|
||||
void stream_deinit(void)
|
||||
{
|
||||
}
|
||||
|
||||
void stream_init(uint32_t our_sn)
|
||||
{
|
||||
#if defined(STREAM_DEBUG)
|
||||
DEBUG_PRINTF("\r\nSTREAM init\r\n");
|
||||
#endif
|
||||
|
||||
if (saved_settings.mode == MODE_STREAM_TX)
|
||||
rfm22_init_tx_stream(saved_settings.min_frequency_Hz, saved_settings.max_frequency_Hz);
|
||||
else
|
||||
if (saved_settings.mode == MODE_STREAM_RX)
|
||||
rfm22_init_rx_stream(saved_settings.min_frequency_Hz, saved_settings.max_frequency_Hz);
|
||||
|
||||
rfm22_TxDataByte_SetCallback(stream_TxDataByteCallback);
|
||||
rfm22_RxData_SetCallback(stream_RxDataCallback);
|
||||
|
||||
rfm22_setFreqCalibration(saved_settings.rf_xtal_cap);
|
||||
rfm22_setNominalCarrierFrequency(saved_settings.frequency_Hz);
|
||||
rfm22_setDatarate(saved_settings.max_rf_bandwidth, FALSE);
|
||||
rfm22_setTxPower(saved_settings.max_tx_power);
|
||||
|
||||
rfm22_setTxStream(); // TEST ONLY
|
||||
}
|
||||
|
||||
// *************************************************************
|
@ -1,218 +0,0 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file transparent_comms.c
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @brief Serial communication port handling routines
|
||||
* @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 <string.h>
|
||||
|
||||
#include "stm32f10x.h"
|
||||
#include "gpio_in.h"
|
||||
#include "transparent_comms.h"
|
||||
#include "packet_handler.h"
|
||||
#include "saved_settings.h"
|
||||
#include "main.h"
|
||||
#include "pios_usb.h" /* PIOS_USB_* */
|
||||
|
||||
#if defined(PIOS_COM_DEBUG)
|
||||
#define TRANS_DEBUG
|
||||
#endif
|
||||
|
||||
// *****************************************************************************
|
||||
// local variables
|
||||
|
||||
uint32_t trans_previous_com_port = 0;
|
||||
|
||||
volatile uint16_t trans_rx_timer = 0;
|
||||
volatile uint16_t trans_tx_timer = 0;
|
||||
|
||||
uint8_t trans_temp_buffer1[128];
|
||||
|
||||
uint8_t trans_temp_buffer2[128];
|
||||
uint16_t trans_temp_buffer2_wr;
|
||||
|
||||
// *****************************************************************************
|
||||
// can be called from an interrupt if you wish
|
||||
|
||||
void trans_1ms_tick(void)
|
||||
{ // call this once every 1ms
|
||||
if (trans_rx_timer < 0xffff) trans_rx_timer++;
|
||||
if (trans_tx_timer < 0xffff) trans_tx_timer++;
|
||||
}
|
||||
|
||||
// *****************************************************************************
|
||||
// call this as often as possible - not from an interrupt
|
||||
|
||||
void trans_process(void)
|
||||
{ // copy data from comm-port RX buffer to RF packet handler TX buffer, and from RF packet handler RX buffer to comm-port TX buffer
|
||||
|
||||
// ********************
|
||||
// decide which comm-port we are using (usart or usb)
|
||||
|
||||
bool usb_comms = false; // TRUE if we are using the usb port for comms.
|
||||
uint32_t comm_port = PIOS_COM_SERIAL; // default to using the usart comm-port
|
||||
|
||||
#if defined(PIOS_INCLUDE_USB)
|
||||
if (PIOS_USB_CheckAvailable(0))
|
||||
{ // USB comms is up, use the USB comm-port instead of the USART comm-port
|
||||
usb_comms = true;
|
||||
comm_port = PIOS_COM_TELEM_USB;
|
||||
}
|
||||
#endif
|
||||
|
||||
// ********************
|
||||
// check to see if the local communication port has changed (usart/usb)
|
||||
|
||||
if (trans_previous_com_port == 0 && trans_previous_com_port != comm_port)
|
||||
{ // the local communications port has changed .. remove any data in the buffers
|
||||
trans_temp_buffer2_wr = 0;
|
||||
}
|
||||
else
|
||||
if (usb_comms)
|
||||
{ // we're using the USB for comms - keep the USART rx buffer empty
|
||||
uint8_t c;
|
||||
while (PIOS_COM_ReceiveBuffer(PIOS_COM_SERIAL, &c, 1, 0) > 0);
|
||||
}
|
||||
|
||||
trans_previous_com_port = comm_port; // remember the current comm-port we are using
|
||||
|
||||
// ********************
|
||||
|
||||
uint16_t connection_index = 0; // the RF connection we are using
|
||||
|
||||
// ********************
|
||||
// send the data received down the comm-port to the RF packet handler TX buffer
|
||||
|
||||
if (saved_settings.mode == MODE_NORMAL || saved_settings.mode == MODE_STREAM_TX)
|
||||
{
|
||||
// free space size in the RF packet handler tx buffer
|
||||
uint16_t ph_num = ph_putData_free(connection_index);
|
||||
|
||||
// set the USART RTS handshaking line
|
||||
if (!usb_comms)
|
||||
{
|
||||
if (ph_num < 32 || !ph_connected(connection_index))
|
||||
SERIAL_RTS_CLEAR; // lower the USART RTS line - we don't have space in the buffer for anymore bytes
|
||||
else
|
||||
SERIAL_RTS_SET; // release the USART RTS line - we have space in the buffer for now bytes
|
||||
}
|
||||
else
|
||||
SERIAL_RTS_SET; // release the USART RTS line
|
||||
|
||||
// limit number of bytes we will get to the size of the temp buffer
|
||||
if (ph_num > sizeof(trans_temp_buffer1))
|
||||
ph_num = sizeof(trans_temp_buffer1);
|
||||
|
||||
// copy data received down the comm-port into our temp buffer
|
||||
register uint16_t bytes_saved = 0;
|
||||
bytes_saved = PIOS_COM_ReceiveBuffer(comm_port, trans_temp_buffer1, ph_num, 0);
|
||||
|
||||
// put the received comm-port data bytes into the RF packet handler TX buffer
|
||||
if (bytes_saved > 0)
|
||||
{
|
||||
trans_rx_timer = 0;
|
||||
ph_putData(connection_index, trans_temp_buffer1, bytes_saved);
|
||||
}
|
||||
}
|
||||
else
|
||||
{ // empty the comm-ports rx buffer
|
||||
uint8_t c;
|
||||
while (PIOS_COM_ReceiveBuffer(comm_port, &c, 1, 0) > 0);
|
||||
}
|
||||
|
||||
// ********************
|
||||
// send the data received via the RF link out the comm-port
|
||||
|
||||
if (saved_settings.mode == MODE_NORMAL || saved_settings.mode == MODE_STREAM_RX)
|
||||
{
|
||||
if (trans_temp_buffer2_wr < sizeof(trans_temp_buffer2))
|
||||
{
|
||||
// get number of data bytes received via the RF link
|
||||
uint16_t ph_num = ph_getData_used(connection_index);
|
||||
|
||||
// limit to how much space we have in the temp buffer
|
||||
if (ph_num > sizeof(trans_temp_buffer2) - trans_temp_buffer2_wr)
|
||||
ph_num = sizeof(trans_temp_buffer2) - trans_temp_buffer2_wr;
|
||||
|
||||
if (ph_num > 0)
|
||||
{ // fetch the data bytes received via the RF link and save into our temp buffer
|
||||
ph_num = ph_getData(connection_index, trans_temp_buffer2 + trans_temp_buffer2_wr, ph_num);
|
||||
trans_temp_buffer2_wr += ph_num;
|
||||
}
|
||||
}
|
||||
|
||||
#if (defined(PIOS_COM_DEBUG) && (PIOS_COM_DEBUG == PIOS_COM_SERIAL))
|
||||
if (!usb_comms)
|
||||
{ // the serial-port is being used for debugging - don't send data down it
|
||||
trans_temp_buffer2_wr = 0;
|
||||
trans_tx_timer = 0;
|
||||
return;
|
||||
}
|
||||
#endif
|
||||
|
||||
if (trans_temp_buffer2_wr > 0)
|
||||
{ // we have data in our temp buffer that needs sending out the comm-port
|
||||
|
||||
if (usb_comms || (!usb_comms && GPIO_IN(SERIAL_CTS_PIN)))
|
||||
{ // we are OK to send the data out the comm-port
|
||||
|
||||
// send the data out the comm-port
|
||||
int32_t res = PIOS_COM_SendBufferNonBlocking(comm_port, trans_temp_buffer2, trans_temp_buffer2_wr); // this one doesn't work properly with USB :(
|
||||
if (res >= 0)
|
||||
{ // data was sent out the comm-port OK .. remove the sent data from the temp buffer
|
||||
trans_temp_buffer2_wr = 0;
|
||||
trans_tx_timer = 0;
|
||||
}
|
||||
else
|
||||
{ // failed to send the data out the comm-port
|
||||
#if defined(TRANS_DEBUG)
|
||||
DEBUG_PRINTF("PIOS_COM_SendBuffer %d %d\r\n", trans_temp_buffer2_wr, res);
|
||||
#endif
|
||||
|
||||
if (trans_tx_timer >= 5000)
|
||||
trans_temp_buffer2_wr = 0; // seems we can't send our data for at least the last 5 seconds - delete it
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
else
|
||||
{ // empty the buffer
|
||||
trans_temp_buffer2_wr = 0;
|
||||
trans_tx_timer = 0;
|
||||
}
|
||||
|
||||
// ********************
|
||||
}
|
||||
|
||||
// *****************************************************************************
|
||||
|
||||
void trans_init(void)
|
||||
{
|
||||
trans_previous_com_port = 0;
|
||||
|
||||
trans_temp_buffer2_wr = 0;
|
||||
|
||||
trans_rx_timer = 0;
|
||||
trans_tx_timer = 0;
|
||||
}
|
||||
|
||||
// *****************************************************************************
|
@ -1,71 +0,0 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file watchdog.c
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @brief Modem packet handling routines
|
||||
* @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 "stm32f10x_iwdg.h"
|
||||
#include "stm32f10x_dbgmcu.h"
|
||||
|
||||
/**
|
||||
* @brief Initialize the watchdog timer for a specified timeout
|
||||
*
|
||||
* It is important to note that this function returns the achieved timeout
|
||||
* for this hardware. For hardware indendence this should be checked when
|
||||
* scheduling updates. Other hardware dependent details may need to be
|
||||
* considered such as a window time which sets a minimum update time,
|
||||
* and this function should return a recommended delay for clearing.
|
||||
*
|
||||
* For the STM32 nominal clock rate is 32 khz, but for the maximum clock rate of
|
||||
* 60 khz and a prescalar of 4 yields a clock rate of 15 khz. The delay that is
|
||||
* set in the watchdog assumes the nominal clock rate, but the delay for FreeRTOS
|
||||
* to use is 75% of the minimal delay.
|
||||
*
|
||||
* @param[in] delayMs The delay period in ms
|
||||
* @returns Maximum recommended delay between updates
|
||||
*/
|
||||
uint16_t watchdog_Init(uint16_t delayMs)
|
||||
{
|
||||
uint16_t delay = ((uint32_t)delayMs * 60) / 16;
|
||||
if (delay > 0x0fff)
|
||||
delay = 0x0fff;
|
||||
|
||||
DBGMCU_Config(DBGMCU_IWDG_STOP, ENABLE); // make the watchdog stop counting in debug mode
|
||||
IWDG_WriteAccessCmd(IWDG_WriteAccess_Enable);
|
||||
IWDG_SetPrescaler(IWDG_Prescaler_16);
|
||||
IWDG_SetReload(delay);
|
||||
IWDG_ReloadCounter();
|
||||
IWDG_Enable();
|
||||
|
||||
return ((((uint32_t)delay * 16) / 60) * .75f);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Clear the watchdog timer
|
||||
*
|
||||
* This function must be called at the appropriate delay to prevent a reset event occuring
|
||||
*/
|
||||
void watchdog_Clear(void)
|
||||
{
|
||||
IWDG_ReloadCounter();
|
||||
}
|
@ -10,9 +10,11 @@ DriverVer=10/15/2009,1.0.0.0
|
||||
|
||||
[DeviceList.NTx86]
|
||||
%CopterControl%= DriverInstall,USB\VID_20A0&PID_415b&MI_00
|
||||
%PipXtreme%= DriverInstall,USB\VID_20A0&PID_415c&MI_00
|
||||
|
||||
[DeviceList.NTamd64]
|
||||
%CopterControl%= DriverInstall,USB\VID_20A0&PID_415b&MI_00
|
||||
%PipXtreme%= DriverInstall,USB\VID_20A0&PID_415c&MI_00
|
||||
|
||||
[DriverInstall]
|
||||
include=mdmcpq.inf
|
||||
@ -30,3 +32,4 @@ HKR,,EnumPropPages32,,"MsPorts.dll,SerialPortPropPageProvider"
|
||||
[Strings]
|
||||
ProviderName = "CDC Driver"
|
||||
CopterControl = "OpenPilot CDC Driver"
|
||||
PipXtreme = "OpenPilot CDC Driver"
|
||||
|
@ -45,13 +45,18 @@ typedef struct {
|
||||
|
||||
typedef void* UAVTalkConnection;
|
||||
|
||||
typedef enum {UAVTALK_STATE_ERROR=0, UAVTALK_STATE_SYNC, UAVTALK_STATE_TYPE, UAVTALK_STATE_SIZE, UAVTALK_STATE_OBJID, UAVTALK_STATE_INSTID, UAVTALK_STATE_DATA, UAVTALK_STATE_CS, UAVTALK_STATE_COMPLETE} UAVTalkRxState;
|
||||
|
||||
// Public functions
|
||||
UAVTalkConnection UAVTalkInitialize(UAVTalkOutputStream outputStream);
|
||||
int32_t UAVTalkSetOutputStream(UAVTalkConnection connection, UAVTalkOutputStream outputStream);
|
||||
UAVTalkOutputStream UAVTalkGetOutputStream(UAVTalkConnection connection);
|
||||
int32_t UAVTalkSendObject(UAVTalkConnection connection, UAVObjHandle obj, uint16_t instId, uint8_t acked, int32_t timeoutMs);
|
||||
int32_t UAVTalkSendObjectRequest(UAVTalkConnection connection, UAVObjHandle obj, uint16_t instId, int32_t timeoutMs);
|
||||
int32_t UAVTalkProcessInputStream(UAVTalkConnection connection, uint8_t rxbyte);
|
||||
int32_t UAVTalkSendAck(UAVTalkConnection connectionHandle, UAVObjHandle obj, uint16_t instId);
|
||||
int32_t UAVTalkSendNack(UAVTalkConnection connectionHandle, uint32_t objId);
|
||||
UAVTalkRxState UAVTalkProcessInputStream(UAVTalkConnection connection, uint8_t rxbyte);
|
||||
UAVTalkRxState UAVTalkProcessInputStreamQuiet(UAVTalkConnection connection, uint8_t rxbyte);
|
||||
void UAVTalkGetStats(UAVTalkConnection connection, UAVTalkStats *stats);
|
||||
void UAVTalkResetStats(UAVTalkConnection connection);
|
||||
|
||||
|
@ -55,8 +55,6 @@ typedef uint8_t uavtalk_checksum;
|
||||
#define UAVTALK_MIN_PACKET_LENGTH UAVTALK_MAX_HEADER_LENGTH + UAVTALK_CHECKSUM_LENGTH
|
||||
#define UAVTALK_MAX_PACKET_LENGTH UAVTALK_MIN_PACKET_LENGTH + UAVTALK_MAX_PAYLOAD_LENGTH
|
||||
|
||||
typedef enum {UAVTALK_STATE_SYNC, UAVTALK_STATE_TYPE, UAVTALK_STATE_SIZE, UAVTALK_STATE_OBJID, UAVTALK_STATE_INSTID, UAVTALK_STATE_DATA, UAVTALK_STATE_CS} UAVTalkRxState;
|
||||
|
||||
typedef struct {
|
||||
UAVObjHandle obj;
|
||||
uint8_t type;
|
||||
|
@ -252,16 +252,18 @@ static int32_t objectTransaction(UAVTalkConnectionData *connection, UAVObjHandle
|
||||
* Process an byte from the telemetry stream.
|
||||
* \param[in] connection UAVTalkConnection to be used
|
||||
* \param[in] rxbyte Received byte
|
||||
* \return 0 Success
|
||||
* \return -1 Failure
|
||||
* \return UAVTalkRxState
|
||||
*/
|
||||
int32_t UAVTalkProcessInputStream(UAVTalkConnection connectionHandle, uint8_t rxbyte)
|
||||
UAVTalkRxState UAVTalkProcessInputStreamQuiet(UAVTalkConnection connectionHandle, uint8_t rxbyte)
|
||||
{
|
||||
UAVTalkConnectionData *connection;
|
||||
CHECKCONHANDLE(connectionHandle,connection,return -1);
|
||||
|
||||
UAVTalkInputProcessor *iproc = &connection->iproc;
|
||||
++connection->stats.rxBytes;
|
||||
|
||||
if (iproc->state == UAVTALK_STATE_ERROR || iproc->state == UAVTALK_STATE_COMPLETE)
|
||||
iproc->state = UAVTALK_STATE_SYNC;
|
||||
|
||||
if (iproc->rxPacketLength < 0xffff)
|
||||
iproc->rxPacketLength++; // update packet byte count
|
||||
@ -288,7 +290,7 @@ int32_t UAVTalkProcessInputStream(UAVTalkConnection connectionHandle, uint8_t rx
|
||||
|
||||
if ((rxbyte & UAVTALK_TYPE_MASK) != UAVTALK_TYPE_VER)
|
||||
{
|
||||
iproc->state = UAVTALK_STATE_SYNC;
|
||||
iproc->state = UAVTALK_STATE_ERROR;
|
||||
break;
|
||||
}
|
||||
|
||||
@ -316,7 +318,7 @@ int32_t UAVTalkProcessInputStream(UAVTalkConnection connectionHandle, uint8_t rx
|
||||
|
||||
if (iproc->packet_size < UAVTALK_MIN_HEADER_LENGTH || iproc->packet_size > UAVTALK_MAX_HEADER_LENGTH + UAVTALK_MAX_PAYLOAD_LENGTH)
|
||||
{ // incorrect packet size
|
||||
iproc->state = UAVTALK_STATE_SYNC;
|
||||
iproc->state = UAVTALK_STATE_ERROR;
|
||||
break;
|
||||
}
|
||||
|
||||
@ -335,17 +337,8 @@ int32_t UAVTalkProcessInputStream(UAVTalkConnection connectionHandle, uint8_t rx
|
||||
if (iproc->rxCount < 4)
|
||||
break;
|
||||
|
||||
// Search for object, if not found reset state machine
|
||||
// except if we got a OBJ_REQ for an object which does not
|
||||
// exist, in which case we'll send a NACK
|
||||
|
||||
// Search for object.
|
||||
iproc->obj = UAVObjGetByID(iproc->objId);
|
||||
if (iproc->obj == 0 && iproc->type != UAVTALK_TYPE_OBJ_REQ)
|
||||
{
|
||||
connection->stats.rxErrors++;
|
||||
iproc->state = UAVTALK_STATE_SYNC;
|
||||
break;
|
||||
}
|
||||
|
||||
// Determine data length
|
||||
if (iproc->type == UAVTALK_TYPE_OBJ_REQ || iproc->type == UAVTALK_TYPE_ACK || iproc->type == UAVTALK_TYPE_NACK)
|
||||
@ -355,15 +348,24 @@ int32_t UAVTalkProcessInputStream(UAVTalkConnection connectionHandle, uint8_t rx
|
||||
}
|
||||
else
|
||||
{
|
||||
iproc->length = UAVObjGetNumBytes(iproc->obj);
|
||||
iproc->instanceLength = (UAVObjIsSingleInstance(iproc->obj) ? 0 : 2);
|
||||
if (iproc->obj)
|
||||
{
|
||||
iproc->length = UAVObjGetNumBytes(iproc->obj);
|
||||
iproc->instanceLength = (UAVObjIsSingleInstance(iproc->obj) ? 0 : 2);
|
||||
}
|
||||
else
|
||||
{
|
||||
// We don't know if it's a multi-instance object, so just assume it's 0.
|
||||
iproc->instanceLength = 0;
|
||||
iproc->length = iproc->packet_size - iproc->rxPacketLength;
|
||||
}
|
||||
}
|
||||
|
||||
// Check length and determine next state
|
||||
if (iproc->length >= UAVTALK_MAX_PAYLOAD_LENGTH)
|
||||
{
|
||||
connection->stats.rxErrors++;
|
||||
iproc->state = UAVTALK_STATE_SYNC;
|
||||
iproc->state = UAVTALK_STATE_ERROR;
|
||||
break;
|
||||
}
|
||||
|
||||
@ -371,34 +373,30 @@ int32_t UAVTalkProcessInputStream(UAVTalkConnection connectionHandle, uint8_t rx
|
||||
if ((iproc->rxPacketLength + iproc->instanceLength + iproc->length) != iproc->packet_size)
|
||||
{ // packet error - mismatched packet size
|
||||
connection->stats.rxErrors++;
|
||||
iproc->state = UAVTALK_STATE_SYNC;
|
||||
iproc->state = UAVTALK_STATE_ERROR;
|
||||
break;
|
||||
}
|
||||
|
||||
iproc->instId = 0;
|
||||
if (iproc->obj == 0)
|
||||
if (iproc->type == UAVTALK_TYPE_NACK)
|
||||
{
|
||||
// If this is a NACK, we skip to Checksum
|
||||
iproc->state = UAVTALK_STATE_CS;
|
||||
iproc->rxCount = 0;
|
||||
|
||||
}
|
||||
// Check if this is a single instance object (i.e. if the instance ID field is coming next)
|
||||
else if (UAVObjIsSingleInstance(iproc->obj))
|
||||
else if ((iproc->obj != 0) && !UAVObjIsSingleInstance(iproc->obj))
|
||||
{
|
||||
iproc->state = UAVTALK_STATE_INSTID;
|
||||
}
|
||||
else
|
||||
{
|
||||
// If there is a payload get it, otherwise receive checksum
|
||||
if (iproc->length > 0)
|
||||
iproc->state = UAVTALK_STATE_DATA;
|
||||
else
|
||||
iproc->state = UAVTALK_STATE_CS;
|
||||
|
||||
iproc->rxCount = 0;
|
||||
}
|
||||
else
|
||||
{
|
||||
iproc->state = UAVTALK_STATE_INSTID;
|
||||
iproc->rxCount = 0;
|
||||
}
|
||||
iproc->rxCount = 0;
|
||||
|
||||
break;
|
||||
|
||||
@ -441,33 +439,84 @@ int32_t UAVTalkProcessInputStream(UAVTalkConnection connectionHandle, uint8_t rx
|
||||
if (rxbyte != iproc->cs)
|
||||
{ // packet error - faulty CRC
|
||||
connection->stats.rxErrors++;
|
||||
iproc->state = UAVTALK_STATE_SYNC;
|
||||
iproc->state = UAVTALK_STATE_ERROR;
|
||||
break;
|
||||
}
|
||||
|
||||
if (iproc->rxPacketLength != (iproc->packet_size + 1))
|
||||
{ // packet error - mismatched packet size
|
||||
connection->stats.rxErrors++;
|
||||
iproc->state = UAVTALK_STATE_SYNC;
|
||||
iproc->state = UAVTALK_STATE_ERROR;
|
||||
break;
|
||||
}
|
||||
|
||||
xSemaphoreTakeRecursive(connection->lock, portMAX_DELAY);
|
||||
receiveObject(connection, iproc->type, iproc->objId, iproc->instId, connection->rxBuffer, iproc->length);
|
||||
|
||||
connection->stats.rxObjectBytes += iproc->length;
|
||||
connection->stats.rxObjects++;
|
||||
xSemaphoreGiveRecursive(connection->lock);
|
||||
|
||||
iproc->state = UAVTALK_STATE_SYNC;
|
||||
|
||||
iproc->state = UAVTALK_STATE_COMPLETE;
|
||||
break;
|
||||
|
||||
default:
|
||||
connection->stats.rxErrors++;
|
||||
iproc->state = UAVTALK_STATE_SYNC;
|
||||
iproc->state = UAVTALK_STATE_ERROR;
|
||||
}
|
||||
|
||||
// Done
|
||||
return 0;
|
||||
return iproc->state;
|
||||
}
|
||||
|
||||
/**
|
||||
* Process an byte from the telemetry stream.
|
||||
* \param[in] connection UAVTalkConnection to be used
|
||||
* \param[in] rxbyte Received byte
|
||||
* \return UAVTalkRxState
|
||||
*/
|
||||
UAVTalkRxState UAVTalkProcessInputStream(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;
|
||||
|
||||
xSemaphoreTakeRecursive(connection->lock, portMAX_DELAY);
|
||||
receiveObject(connection, iproc->type, iproc->objId, iproc->instId, connection->rxBuffer, iproc->length);
|
||||
xSemaphoreGiveRecursive(connection->lock);
|
||||
}
|
||||
|
||||
return state;
|
||||
}
|
||||
|
||||
/**
|
||||
* Send a ACK through the telemetry link.
|
||||
* \param[in] connectionHandle UAVTalkConnection to be used
|
||||
* \param[in] objId Object ID to send a NACK for
|
||||
* \return 0 Success
|
||||
* \return -1 Failure
|
||||
*/
|
||||
int32_t UAVTalkSendAck(UAVTalkConnection connectionHandle, UAVObjHandle obj, uint16_t instId)
|
||||
{
|
||||
UAVTalkConnectionData *connection;
|
||||
CHECKCONHANDLE(connectionHandle,connection,return -1);
|
||||
|
||||
return sendObject(connection, obj, instId, UAVTALK_TYPE_ACK);
|
||||
}
|
||||
|
||||
/**
|
||||
* Send a NACK through the telemetry link.
|
||||
* \param[in] connectionHandle UAVTalkConnection to be used
|
||||
* \param[in] objId Object ID to send a NACK for
|
||||
* \return 0 Success
|
||||
* \return -1 Failure
|
||||
*/
|
||||
int32_t UAVTalkSendNack(UAVTalkConnection connectionHandle, uint32_t objId)
|
||||
{
|
||||
UAVTalkConnectionData *connection;
|
||||
CHECKCONHANDLE(connectionHandle,connection,return -1);
|
||||
|
||||
return sendNack(connection, objId);
|
||||
}
|
||||
|
||||
/**
|
||||
@ -494,7 +543,7 @@ static int32_t receiveObject(UAVTalkConnectionData *connection, uint8_t type, ui
|
||||
switch (type) {
|
||||
case UAVTALK_TYPE_OBJ:
|
||||
// All instances, not allowed for OBJ messages
|
||||
if (instId != UAVOBJ_ALL_INSTANCES)
|
||||
if (obj && (instId != UAVOBJ_ALL_INSTANCES))
|
||||
{
|
||||
// Unpack object, if the instance does not exist it will be created!
|
||||
UAVObjUnpack(obj, instId, data);
|
||||
@ -508,7 +557,7 @@ static int32_t receiveObject(UAVTalkConnectionData *connection, uint8_t type, ui
|
||||
break;
|
||||
case UAVTALK_TYPE_OBJ_ACK:
|
||||
// All instances, not allowed for OBJ_ACK messages
|
||||
if (instId != UAVOBJ_ALL_INSTANCES)
|
||||
if (obj && (instId != UAVOBJ_ALL_INSTANCES))
|
||||
{
|
||||
// Unpack object, if the instance does not exist it will be created!
|
||||
if ( UAVObjUnpack(obj, instId, data) == 0 )
|
||||
@ -538,7 +587,7 @@ static int32_t receiveObject(UAVTalkConnectionData *connection, uint8_t type, ui
|
||||
break;
|
||||
case UAVTALK_TYPE_ACK:
|
||||
// All instances, not allowed for ACK messages
|
||||
if (instId != UAVOBJ_ALL_INSTANCES)
|
||||
if (obj && (instId != UAVOBJ_ALL_INSTANCES))
|
||||
{
|
||||
// Check if an ack is pending
|
||||
updateAck(connection, obj, instId);
|
||||
|
@ -27,6 +27,10 @@
|
||||
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
*/
|
||||
#include <pios_config.h>
|
||||
#include <pios_board_info.h>
|
||||
|
||||
#define BOARD_REVISION_CC 1
|
||||
#define BOARD_REVISION_CC3D 2
|
||||
|
||||
#if defined(PIOS_INCLUDE_LED)
|
||||
|
||||
@ -59,6 +63,7 @@ static const struct pios_led pios_leds_cc3d[] = {
|
||||
.GPIO_Speed = GPIO_Speed_50MHz,
|
||||
},
|
||||
},
|
||||
.remap = GPIO_Remap_SWJ_JTAGDisable,
|
||||
},
|
||||
};
|
||||
|
||||
@ -67,6 +72,15 @@ static const struct pios_led_cfg pios_led_cfg_cc3d = {
|
||||
.num_leds = NELEMENTS(pios_leds_cc3d),
|
||||
};
|
||||
|
||||
const struct pios_led_cfg * PIOS_BOARD_HW_DEFS_GetLedCfg (uint32_t board_revision)
|
||||
{
|
||||
switch (board_revision) {
|
||||
case BOARD_REVISION_CC: return &pios_led_cfg_cc;
|
||||
case BOARD_REVISION_CC3D: return &pios_led_cfg_cc3d;
|
||||
default: return NULL;
|
||||
}
|
||||
}
|
||||
|
||||
#endif /* PIOS_INCLUDE_LED */
|
||||
|
||||
#if defined(PIOS_INCLUDE_SPI)
|
||||
|
@ -1,5 +1,58 @@
|
||||
#include <pios_config.h>
|
||||
|
||||
#if defined(PIOS_INCLUDE_LED)
|
||||
|
||||
#include <pios_led_priv.h>
|
||||
static const struct pios_led pios_leds[] = {
|
||||
[PIOS_LED_USB] = {
|
||||
.pin = {
|
||||
.gpio = GPIOA,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_3,
|
||||
.GPIO_Mode = GPIO_Mode_Out_PP,
|
||||
.GPIO_Speed = GPIO_Speed_50MHz,
|
||||
},
|
||||
},
|
||||
},
|
||||
[PIOS_LED_LINK] = {
|
||||
.pin = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_5,
|
||||
.GPIO_Mode = GPIO_Mode_Out_PP,
|
||||
.GPIO_Speed = GPIO_Speed_50MHz,
|
||||
},
|
||||
},
|
||||
},
|
||||
[PIOS_LED_RX] = {
|
||||
.pin = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_6,
|
||||
.GPIO_Mode = GPIO_Mode_Out_PP,
|
||||
.GPIO_Speed = GPIO_Speed_50MHz,
|
||||
},
|
||||
},
|
||||
},
|
||||
[PIOS_LED_TX] = {
|
||||
.pin = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_7,
|
||||
.GPIO_Mode = GPIO_Mode_Out_PP,
|
||||
.GPIO_Speed = GPIO_Speed_50MHz,
|
||||
},
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
static const struct pios_led_cfg pios_led_cfg = {
|
||||
.leds = pios_leds,
|
||||
.num_leds = NELEMENTS(pios_leds),
|
||||
};
|
||||
|
||||
#endif /* PIOS_INCLUDE_LED */
|
||||
|
||||
#if defined(PIOS_INCLUDE_SPI)
|
||||
|
||||
#include <pios_spi_priv.h>
|
||||
@ -74,9 +127,9 @@ static const struct pios_spi_cfg pios_spi_port_cfg =
|
||||
},
|
||||
},
|
||||
},
|
||||
|
||||
.slave_count = 1,
|
||||
.ssel =
|
||||
{
|
||||
{{
|
||||
.gpio = GPIOA,
|
||||
.init =
|
||||
{
|
||||
@ -84,7 +137,7 @@ static const struct pios_spi_cfg pios_spi_port_cfg =
|
||||
.GPIO_Speed = GPIO_Speed_10MHz,
|
||||
.GPIO_Mode = GPIO_Mode_Out_PP,
|
||||
},
|
||||
},
|
||||
}},
|
||||
.sclk =
|
||||
{
|
||||
.gpio = GPIOA,
|
||||
@ -181,6 +234,86 @@ void PIOS_ADC_handler() {
|
||||
|
||||
#endif /* PIOS_INCLUDE_ADC */
|
||||
|
||||
#if defined(PIOS_INCLUDE_TIM)
|
||||
|
||||
#include "pios_tim_priv.h"
|
||||
|
||||
static const TIM_TimeBaseInitTypeDef tim_1_2_3_4_time_base = {
|
||||
.TIM_Prescaler = (PIOS_MASTER_CLOCK / 1000000) - 1,
|
||||
.TIM_ClockDivision = TIM_CKD_DIV1,
|
||||
.TIM_CounterMode = TIM_CounterMode_Up,
|
||||
.TIM_Period = ((1000000 / PIOS_SERVO_UPDATE_HZ) - 1),
|
||||
.TIM_RepetitionCounter = 0x0000,
|
||||
};
|
||||
|
||||
static const struct pios_tim_clock_cfg tim_1_cfg = {
|
||||
.timer = TIM1,
|
||||
.time_base_init = &tim_1_2_3_4_time_base,
|
||||
.irq = {
|
||||
.init = {
|
||||
.NVIC_IRQChannel = TIM1_CC_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
static const struct pios_tim_clock_cfg tim_2_cfg = {
|
||||
.timer = TIM2,
|
||||
.time_base_init = &tim_1_2_3_4_time_base,
|
||||
.irq = {
|
||||
.init = {
|
||||
.NVIC_IRQChannel = TIM2_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
static const struct pios_tim_clock_cfg tim_3_cfg = {
|
||||
.timer = TIM3,
|
||||
.time_base_init = &tim_1_2_3_4_time_base,
|
||||
.irq = {
|
||||
.init = {
|
||||
.NVIC_IRQChannel = TIM3_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
static const struct pios_tim_clock_cfg tim_4_cfg = {
|
||||
.timer = TIM4,
|
||||
.time_base_init = &tim_1_2_3_4_time_base,
|
||||
.irq = {
|
||||
.init = {
|
||||
.NVIC_IRQChannel = TIM4_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
static const struct pios_tim_channel pios_tim_ppm_flexi_port = {
|
||||
.timer = TIM2,
|
||||
.timer_chan = TIM_Channel_4,
|
||||
.pin = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_11,
|
||||
.GPIO_Mode = GPIO_Mode_IPD,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
},
|
||||
},
|
||||
.remap = GPIO_PartialRemap2_TIM2,
|
||||
};
|
||||
|
||||
#endif /* PIOS_INCLUDE_TIM */
|
||||
|
||||
#if defined(PIOS_INCLUDE_USART)
|
||||
|
||||
#include <pios_usart_priv.h>
|
||||
@ -232,6 +365,42 @@ static const struct pios_usart_cfg pios_usart_serial_cfg =
|
||||
},
|
||||
};
|
||||
|
||||
static const struct pios_usart_cfg pios_usart_telem_flexi_cfg = {
|
||||
.regs = USART3,
|
||||
.init = {
|
||||
.USART_BaudRate = 57600,
|
||||
.USART_WordLength = USART_WordLength_8b,
|
||||
.USART_Parity = USART_Parity_No,
|
||||
.USART_StopBits = USART_StopBits_1,
|
||||
.USART_HardwareFlowControl = USART_HardwareFlowControl_None,
|
||||
.USART_Mode = USART_Mode_Rx | USART_Mode_Tx,
|
||||
},
|
||||
.irq = {
|
||||
.init = {
|
||||
.NVIC_IRQChannel = USART3_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
.rx = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_11,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
.GPIO_Mode = GPIO_Mode_IPU,
|
||||
},
|
||||
},
|
||||
.tx = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_10,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
.GPIO_Mode = GPIO_Mode_AF_PP,
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
#endif /* PIOS_INCLUDE_USART */
|
||||
|
||||
#if defined(PIOS_INCLUDE_COM)
|
||||
@ -240,34 +409,136 @@ static const struct pios_usart_cfg pios_usart_serial_cfg =
|
||||
|
||||
#endif /* PIOS_INCLUDE_COM */
|
||||
|
||||
// ***********************************************************************************
|
||||
#if defined(PIOS_INCLUDE_RTC)
|
||||
/*
|
||||
* Realtime Clock (RTC)
|
||||
*/
|
||||
#include <pios_rtc_priv.h>
|
||||
|
||||
void PIOS_RTC_IRQ_Handler (void);
|
||||
void RTC_IRQHandler() __attribute__ ((alias ("PIOS_RTC_IRQ_Handler")));
|
||||
static const struct pios_rtc_cfg pios_rtc_main_cfg = {
|
||||
.clksrc = RCC_RTCCLKSource_HSE_Div128,
|
||||
.prescaler = 100,
|
||||
.irq = {
|
||||
.init = {
|
||||
.NVIC_IRQChannel = RTC_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
void PIOS_RTC_IRQ_Handler (void)
|
||||
{
|
||||
PIOS_RTC_irq_handler ();
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
/*
|
||||
* PPM Inputs
|
||||
*/
|
||||
#if defined(PIOS_INCLUDE_PPM)
|
||||
#include <pios_ppm_priv.h>
|
||||
|
||||
const struct pios_ppm_cfg pios_ppm_cfg = {
|
||||
.tim_ic_init = {
|
||||
.TIM_ICPolarity = TIM_ICPolarity_Rising,
|
||||
.TIM_ICSelection = TIM_ICSelection_DirectTI,
|
||||
.TIM_ICPrescaler = TIM_ICPSC_DIV1,
|
||||
.TIM_ICFilter = 0x0,
|
||||
},
|
||||
.channels = &pios_tim_ppm_flexi_port,
|
||||
.num_channels = 1,
|
||||
};
|
||||
|
||||
#endif /* PIOS_INCLUDE_PPM */
|
||||
|
||||
#if defined(PIOS_INCLUDE_RCVR)
|
||||
#include "pios_rcvr_priv.h"
|
||||
|
||||
#endif /* PIOS_INCLUDE_RCVR */
|
||||
|
||||
#if defined(PIOS_INCLUDE_USB)
|
||||
#include "pios_usb_priv.h"
|
||||
|
||||
static const struct pios_usb_cfg pios_usb_main_cfg = {
|
||||
.irq = {
|
||||
.init = {
|
||||
.NVIC_IRQChannel = USB_LP_CAN1_RX0_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_LOW,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
.irq = {
|
||||
.init = {
|
||||
.NVIC_IRQChannel = USB_LP_CAN1_RX0_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_LOW,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
.vsense = {
|
||||
.gpio = GPIOA,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_8,
|
||||
.GPIO_Speed = GPIO_Speed_10MHz,
|
||||
.GPIO_Mode = GPIO_Mode_AF_OD,
|
||||
},
|
||||
}
|
||||
};
|
||||
|
||||
#include "pios_usb_board_data_priv.h"
|
||||
#include "pios_usb_desc_hid_cdc_priv.h"
|
||||
#include "pios_usb_desc_hid_only_priv.h"
|
||||
|
||||
#endif /* PIOS_INCLUDE_USB */
|
||||
|
||||
#if defined(PIOS_INCLUDE_COM_MSG)
|
||||
|
||||
#include <pios_com_msg_priv.h>
|
||||
|
||||
#endif /* PIOS_INCLUDE_COM_MSG */
|
||||
|
||||
#if defined(PIOS_INCLUDE_USB_HID)
|
||||
#include <pios_usb_hid_priv.h>
|
||||
|
||||
const struct pios_usb_hid_cfg pios_usb_hid_cfg = {
|
||||
.data_if = 0,
|
||||
.data_if = 2,
|
||||
.data_rx_ep = 1,
|
||||
.data_tx_ep = 1,
|
||||
};
|
||||
#endif /* PIOS_INCLUDE_USB_HID */
|
||||
|
||||
#endif /* PIOS_INCLUDE_USB_HID */
|
||||
#if defined(PIOS_INCLUDE_USB_CDC)
|
||||
#include <pios_usb_cdc_priv.h>
|
||||
|
||||
const struct pios_usb_cdc_cfg pios_usb_cdc_cfg = {
|
||||
.ctrl_if = 0,
|
||||
.ctrl_tx_ep = 2,
|
||||
|
||||
.data_if = 1,
|
||||
.data_rx_ep = 3,
|
||||
.data_tx_ep = 3,
|
||||
};
|
||||
#endif /* PIOS_INCLUDE_USB_CDC */
|
||||
|
||||
#if defined(PIOS_INCLUDE_FLASH_EEPROM)
|
||||
#include <pios_eeprom.h>
|
||||
|
||||
const struct pios_eeprom_cfg pios_eeprom_cfg = {
|
||||
.base_address = PIOS_FLASH_EEPROM_ADDR,
|
||||
.max_size = PIOS_FLASH_EEPROM_LEN,
|
||||
};
|
||||
#endif /* PIOS_INCLUDE_FLASH_EEPROM */
|
||||
|
||||
#if defined(PIOS_INCLUDE_RFM22B)
|
||||
#include <pios_rfm22b_priv.h>
|
||||
|
||||
#endif /* PIOS_INCLUDE_RFM22B */
|
||||
|
||||
#if defined(PIOS_INCLUDE_PACKET_HANDLER)
|
||||
#include <packet_handler.h>
|
||||
|
||||
// Initialize the packet handler
|
||||
PacketHandlerConfig pios_ph_cfg = {
|
||||
.winSize = PIOS_PH_WIN_SIZE,
|
||||
.maxConnections = PIOS_PH_MAX_CONNECTIONS,
|
||||
};
|
||||
|
||||
#endif /* PIOS_INCLUDE_PACKET_HANDLER */
|
||||
|
@ -20,6 +20,7 @@ HEADERS += configplugin.h \
|
||||
config_pro_hw_widget.h \
|
||||
config_cc_hw_widget.h \
|
||||
configccattitudewidget.h \
|
||||
configpipxtremewidget.h \
|
||||
cfg_vehicletypes/configccpmwidget.h \
|
||||
configstabilizationwidget.h \
|
||||
assertions.h \
|
||||
@ -46,6 +47,7 @@ SOURCES += configplugin.cpp \
|
||||
config_cc_hw_widget.cpp \
|
||||
configccattitudewidget.cpp \
|
||||
configstabilizationwidget.cpp \
|
||||
configpipxtremewidget.cpp \
|
||||
twostep.cpp \
|
||||
legacy-calibration.cpp \
|
||||
gyro-calibration.cpp \
|
||||
@ -75,5 +77,6 @@ FORMS += airframe.ui \
|
||||
camerastabilization.ui \
|
||||
outputchannelform.ui \
|
||||
revosensors.ui \
|
||||
txpid.ui
|
||||
txpid.ui \
|
||||
pipxtreme.ui
|
||||
RESOURCES += configgadget.qrc
|
||||
|
@ -43,7 +43,7 @@ ConfigProHWWidget::ConfigProHWWidget(QWidget *parent) : ConfigTaskWidget(parent)
|
||||
addUAVObjectToWidgetRelation("HwSettings","TelemetrySpeed",m_telemetry->telemetrySpeed);
|
||||
enableControls(false);
|
||||
populateWidgets();
|
||||
refreshWidgetsValues();
|
||||
refreshWidgetsValues(NULL);
|
||||
}
|
||||
|
||||
ConfigProHWWidget::~ConfigProHWWidget()
|
||||
|
@ -90,7 +90,7 @@ ConfigCameraStabilizationWidget::ConfigCameraStabilizationWidget(QWidget *parent
|
||||
connect(m_camerastabilization->camerastabilizationSaveSD, SIGNAL(clicked()), this, SLOT(saveSettings()));
|
||||
connect(m_camerastabilization->camerastabilizationHelp, SIGNAL(clicked()), this, SLOT(openHelp()));
|
||||
|
||||
disbleMouseWheelEvents();
|
||||
disableMouseWheelEvents();
|
||||
}
|
||||
|
||||
ConfigCameraStabilizationWidget::~ConfigCameraStabilizationWidget()
|
||||
|
@ -36,6 +36,7 @@
|
||||
#include "configtxpidwidget.h"
|
||||
#include "config_pro_hw_widget.h"
|
||||
#include "config_cc_hw_widget.h"
|
||||
#include "configpipxtremewidget.h"
|
||||
#include "configrevowidget.h"
|
||||
#include "defaultattitudewidget.h"
|
||||
#include "defaulthwsettingswidget.h"
|
||||
@ -89,8 +90,8 @@ ConfigGadgetWidget::ConfigGadgetWidget(QWidget *parent) : QWidget(parent)
|
||||
qwd = new ConfigTxPIDWidget(this);
|
||||
ftw->insertTab(ConfigGadgetWidget::txpid, qwd, QIcon(":/configgadget/images/txpid.png"), QString("TxPID"));
|
||||
|
||||
// qwd = new ConfigPipXtremeWidget(this);
|
||||
// ftw->insertTab(5, qwd, QIcon(":/configgadget/images/PipXtreme.png"), QString("PipXtreme"));
|
||||
qwd = new ConfigPipXtremeWidget(this);
|
||||
ftw->insertTab(ConfigGadgetWidget::pipxtreme, qwd, QIcon(":/configgadget/images/PipXtreme.png"), QString("PipXtreme"));
|
||||
|
||||
// *********************
|
||||
// Listen to autopilot connection events
|
||||
|
@ -50,7 +50,7 @@ class ConfigGadgetWidget: public QWidget
|
||||
public:
|
||||
ConfigGadgetWidget(QWidget *parent = 0);
|
||||
~ConfigGadgetWidget();
|
||||
enum widgetTabs {hardware=0, aircraft, input, output, sensors, stabilization, camerastabilization, txpid};
|
||||
enum widgetTabs {hardware=0, aircraft, input, output, sensors, stabilization, camerastabilization, txpid, pipxtreme};
|
||||
|
||||
public slots:
|
||||
void onAutopilotConnect();
|
||||
|
@ -242,7 +242,7 @@ void ConfigOutputWidget::sendChannelTest(int index, int value)
|
||||
/**
|
||||
Request the current config from the board (RC Output)
|
||||
*/
|
||||
void ConfigOutputWidget::refreshWidgetsValues()
|
||||
void ConfigOutputWidget::refreshWidgetsValues(UAVObject *)
|
||||
{
|
||||
bool dirty=isDirty();
|
||||
|
||||
|
@ -69,7 +69,7 @@ private:
|
||||
private slots:
|
||||
void stopTests();
|
||||
void disableIfNotMe(UAVObject *obj);
|
||||
virtual void refreshWidgetsValues();
|
||||
virtual void refreshWidgetsValues(UAVObject * obj = NULL);
|
||||
void updateObjectsFromWidgets();
|
||||
void runChannelTests(bool state);
|
||||
void sendChannelTest(int index, int value);
|
||||
|
311
ground/openpilotgcs/src/plugins/config/configpipxtremewidget.cpp
Normal file
311
ground/openpilotgcs/src/plugins/config/configpipxtremewidget.cpp
Normal file
@ -0,0 +1,311 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file configtxpidswidget.cpp
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @addtogroup GCSPlugins GCS Plugins
|
||||
* @{
|
||||
* @addtogroup ConfigPlugin Config Plugin
|
||||
* @{
|
||||
* @brief The Configuration Gadget used to configure the PipXtreme
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* 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 "configpipxtremewidget.h"
|
||||
|
||||
#include <pipxsettings.h>
|
||||
#include <pipxstatus.h>
|
||||
|
||||
ConfigPipXtremeWidget::ConfigPipXtremeWidget(QWidget *parent) : ConfigTaskWidget(parent)
|
||||
{
|
||||
m_pipx = new Ui_PipXtremeWidget();
|
||||
m_pipx->setupUi(this);
|
||||
|
||||
// Connect to the PipXStatus 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*)));
|
||||
} else {
|
||||
qDebug() << "Error: Object is unknown (PipXStatus).";
|
||||
}
|
||||
|
||||
// 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*)));
|
||||
} else {
|
||||
qDebug() << "Error: Object is unknown (PipXSettings).";
|
||||
}
|
||||
|
||||
addApplySaveButtons(m_pipx->Apply, m_pipx->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("PipXStatus", "MinFrequency", m_pipx->MinFrequency);
|
||||
addUAVObjectToWidgetRelation("PipXStatus", "MaxFrequency", m_pipx->MaxFrequency);
|
||||
addUAVObjectToWidgetRelation("PipXStatus", "FrequencyStepSize", m_pipx->FrequencyStepSize);
|
||||
addUAVObjectToWidgetRelation("PipXStatus", "AFC", m_pipx->RxAFC);
|
||||
addUAVObjectToWidgetRelation("PipXStatus", "Retries", m_pipx->Retries);
|
||||
addUAVObjectToWidgetRelation("PipXStatus", "Errors", m_pipx->Errors);
|
||||
addUAVObjectToWidgetRelation("PipXStatus", "UAVTalkErrors", m_pipx->UAVTalkErrors);
|
||||
addUAVObjectToWidgetRelation("PipXStatus", "Resets", m_pipx->Resets);
|
||||
addUAVObjectToWidgetRelation("PipXStatus", "RXRate", m_pipx->RXRate);
|
||||
addUAVObjectToWidgetRelation("PipXStatus", "TXRate", m_pipx->TXRate);
|
||||
|
||||
// Connect to the pair ID radio buttons.
|
||||
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)));
|
||||
|
||||
// Create the timer that is used to timeout the connection to the PipX.
|
||||
timeOut = new QTimer(this);
|
||||
connect(timeOut, SIGNAL(timeout()),this,SLOT(disconnected()));
|
||||
|
||||
//Add scroll bar when necessary
|
||||
QScrollArea *scroll = new QScrollArea;
|
||||
scroll->setWidget(m_pipx->frame_3);
|
||||
m_pipx->verticalLayout_3->addWidget(scroll);
|
||||
|
||||
// Request and update of the setting object.
|
||||
settingsUpdated = false;
|
||||
pipxSettingsObj->requestUpdate();
|
||||
}
|
||||
|
||||
ConfigPipXtremeWidget::~ConfigPipXtremeWidget()
|
||||
{
|
||||
// Do nothing
|
||||
}
|
||||
|
||||
void ConfigPipXtremeWidget::refreshValues()
|
||||
{
|
||||
}
|
||||
|
||||
void ConfigPipXtremeWidget::applySettings()
|
||||
{
|
||||
PipXSettings *pipxSettings = PipXSettings::GetInstance(getObjectManager());
|
||||
PipXSettings::DataFields pipxSettingsData = pipxSettings->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);
|
||||
}
|
||||
|
||||
void ConfigPipXtremeWidget::saveSettings()
|
||||
{
|
||||
//applySettings();
|
||||
UAVObject *obj = PipXSettings::GetInstance(getObjectManager());
|
||||
saveObjectToSD(obj);
|
||||
}
|
||||
|
||||
/*!
|
||||
\brief Called by updates to @PipXStatus
|
||||
*/
|
||||
void ConfigPipXtremeWidget::updateStatus(UAVObject *object)
|
||||
{
|
||||
|
||||
// Restart the disconnection timer.
|
||||
timeOut->start(10000);
|
||||
|
||||
// Request and update of the setting object if we haven't received it yet.
|
||||
if (!settingsUpdated)
|
||||
pipxSettingsObj->requestUpdate();
|
||||
|
||||
// Get the current pairID
|
||||
PipXSettings *pipxSettings = PipXSettings::GetInstance(getObjectManager());
|
||||
quint32 pairID = 0;
|
||||
if (pipxSettings)
|
||||
pipxSettings->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);
|
||||
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);
|
||||
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);
|
||||
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);
|
||||
} else {
|
||||
qDebug() << "PipXtremeGadgetWidget: Count not read PairID field.";
|
||||
}
|
||||
UAVObjectField* pairRssiField = object->getField("PairSignalStrengths");
|
||||
if (pairRssiField) {
|
||||
m_pipx->PairSignalStrength1->setValue(pairRssiField->getValue(0).toInt());
|
||||
m_pipx->PairSignalStrength2->setValue(pairRssiField->getValue(1).toInt());
|
||||
m_pipx->PairSignalStrength3->setValue(pairRssiField->getValue(2).toInt());
|
||||
m_pipx->PairSignalStrength4->setValue(pairRssiField->getValue(3).toInt());
|
||||
} else {
|
||||
qDebug() << "PipXtremeGadgetWidget: Count not read PairID field.";
|
||||
}
|
||||
|
||||
// Update the Description field
|
||||
UAVObjectField* descField = object->getField("Description");
|
||||
if (descField) {
|
||||
/*
|
||||
* This looks like a binary with a description at the end
|
||||
* 4 bytes: header: "OpFw"
|
||||
* 4 bytes: git commit hash (short version of SHA1)
|
||||
* 4 bytes: Unix timestamp of last git commit
|
||||
* 2 bytes: target platform. Should follow same rule as BOARD_TYPE and BOARD_REVISION in board define files.
|
||||
* 26 bytes: commit tag if it is there, otherwise "Unreleased". Zero-padded
|
||||
* ---- 40 bytes limit ---
|
||||
* 20 bytes: SHA1 sum of the firmware.
|
||||
* 40 bytes: free for now.
|
||||
*/
|
||||
char buf[PipXStatus::DESCRIPTION_NUMELEM];
|
||||
for (unsigned int i = 0; i < 26; ++i)
|
||||
buf[i] = descField->getValue(i + 14).toChar().toAscii();
|
||||
buf[26] = '\0';
|
||||
QString descstr(buf);
|
||||
quint32 gitDate = descField->getValue(11).toChar().toAscii() & 0xFF;
|
||||
for (int i = 1; i < 4; i++) {
|
||||
gitDate = gitDate << 8;
|
||||
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);
|
||||
} else {
|
||||
qDebug() << "PipXtremeGadgetWidget: Count not read Description field.";
|
||||
}
|
||||
|
||||
// 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)
|
||||
{
|
||||
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);
|
||||
} else {
|
||||
qDebug() << "PipXtremeGadgetWidget: Count not read Description field.";
|
||||
}
|
||||
|
||||
// Update the DeviceID field
|
||||
UAVObjectField* idField = object->getField("DeviceID");
|
||||
if (idField) {
|
||||
m_pipx->DeviceID->setText(QString::number(idField->getValue().toUInt(), 16).toUpper());
|
||||
} else {
|
||||
qDebug() << "PipXtremeGadgetWidget: Count not read DeviceID field.";
|
||||
}
|
||||
|
||||
// Update the link state
|
||||
UAVObjectField* linkField = object->getField("LinkState");
|
||||
if (linkField) {
|
||||
m_pipx->LinkState->setText(linkField->getValue().toString());
|
||||
} else {
|
||||
qDebug() << "PipXtremeGadgetWidget: Count not read link state field.";
|
||||
}
|
||||
}
|
||||
|
||||
/*!
|
||||
\brief Called by updates to @PipXSettings
|
||||
*/
|
||||
void ConfigPipXtremeWidget::updateSettings(UAVObject *object)
|
||||
{
|
||||
settingsUpdated = true;
|
||||
enableControls(true);
|
||||
}
|
||||
|
||||
void ConfigPipXtremeWidget::disconnected()
|
||||
{
|
||||
settingsUpdated = false;
|
||||
enableControls(false);
|
||||
}
|
||||
|
||||
void ConfigPipXtremeWidget::pairIDToggled(bool checked, quint8 idx)
|
||||
{
|
||||
if(checked)
|
||||
{
|
||||
PipXStatus *pipxStatus = PipXStatus::GetInstance(getObjectManager());
|
||||
PipXSettings *pipxSettings = PipXSettings::GetInstance(getObjectManager());
|
||||
|
||||
if (pipxStatus && pipxSettings)
|
||||
{
|
||||
quint32 pairID = pipxStatus->getPairIDs(idx);
|
||||
if (pairID)
|
||||
pipxSettings->setPairID(pairID);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void ConfigPipXtremeWidget::pair1Toggled(bool checked)
|
||||
{
|
||||
pairIDToggled(checked, 0);
|
||||
}
|
||||
|
||||
void ConfigPipXtremeWidget::pair2Toggled(bool checked)
|
||||
{
|
||||
pairIDToggled(checked, 1);
|
||||
}
|
||||
|
||||
void ConfigPipXtremeWidget::pair3Toggled(bool checked)
|
||||
{
|
||||
pairIDToggled(checked, 2);
|
||||
}
|
||||
|
||||
void ConfigPipXtremeWidget::pair4Toggled(bool checked)
|
||||
{
|
||||
pairIDToggled(checked, 3);
|
||||
}
|
||||
|
||||
/**
|
||||
@}
|
||||
@}
|
||||
*/
|
@ -0,0 +1,71 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file configpipxtremewidget.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @addtogroup GCSPlugins GCS Plugins
|
||||
* @{
|
||||
* @addtogroup ConfigPlugin Config Plugin
|
||||
* @{
|
||||
* @brief The Configuration Gadget used to configure PipXtreme
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* 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 CONFIGPIPXTREMEWIDGET_H
|
||||
#define CONFIGPIPXTREMEWIDGET_H
|
||||
|
||||
#include "ui_pipxtreme.h"
|
||||
#include "configtaskwidget.h"
|
||||
|
||||
class ConfigPipXtremeWidget : public ConfigTaskWidget
|
||||
{
|
||||
Q_OBJECT
|
||||
|
||||
public:
|
||||
ConfigPipXtremeWidget(QWidget *parent = 0);
|
||||
~ConfigPipXtremeWidget();
|
||||
|
||||
public slots:
|
||||
void updateStatus(UAVObject *object1);
|
||||
void updateSettings(UAVObject *object1);
|
||||
|
||||
private:
|
||||
Ui_PipXtremeWidget *m_pipx;
|
||||
|
||||
// The PipXtreme status UAVObject
|
||||
UAVDataObject* pipxStatusObj;
|
||||
|
||||
// The PipXtreme ssettins UAVObject
|
||||
UAVDataObject* pipxSettingsObj;
|
||||
|
||||
bool settingsUpdated;
|
||||
|
||||
// A timer that timesout the connction to the PipX.
|
||||
QTimer *timeOut;
|
||||
|
||||
private slots:
|
||||
void refreshValues();
|
||||
void applySettings();
|
||||
void saveSettings();
|
||||
void disconnected();
|
||||
void pairIDToggled(bool checked, quint8 idx);
|
||||
void pair1Toggled(bool checked);
|
||||
void pair2Toggled(bool checked);
|
||||
void pair3Toggled(bool checked);
|
||||
void pair4Toggled(bool checked);
|
||||
};
|
||||
|
||||
#endif // CONFIGTXPIDWIDGET_H
|
@ -53,7 +53,7 @@ ConfigStabilizationWidget::ConfigStabilizationWidget(QWidget *parent) : ConfigTa
|
||||
|
||||
connect(this,SIGNAL(widgetContentsChanged(QWidget*)),this,SLOT(processLinkedWidgets(QWidget*)));
|
||||
|
||||
disbleMouseWheelEvents();
|
||||
disableMouseWheelEvents();
|
||||
}
|
||||
|
||||
|
||||
|
@ -68,7 +68,7 @@ ConfigTxPIDWidget::ConfigTxPIDWidget(QWidget *parent) : ConfigTaskWidget(parent)
|
||||
populateWidgets();
|
||||
refreshWidgetsValues();
|
||||
|
||||
disbleMouseWheelEvents();
|
||||
disableMouseWheelEvents();
|
||||
}
|
||||
|
||||
ConfigTxPIDWidget::~ConfigTxPIDWidget()
|
||||
|
@ -233,7 +233,7 @@ ConfigVehicleTypeWidget::ConfigVehicleTypeWidget(QWidget *parent) : ConfigTaskWi
|
||||
setupGroundVehicleUI( m_aircraft->groundVehicleType->currentText() );
|
||||
setupFixedWingUI( m_aircraft->fixedWingType->currentText() );
|
||||
|
||||
disbleMouseWheelEvents();
|
||||
disableMouseWheelEvents();
|
||||
}
|
||||
|
||||
|
||||
@ -525,7 +525,7 @@ void ConfigVehicleTypeWidget::updateCustomThrottle2CurveValue(QList<double> list
|
||||
/**
|
||||
Refreshes the current value of the SystemSettings which holds the aircraft type
|
||||
*/
|
||||
void ConfigVehicleTypeWidget::refreshWidgetsValues()
|
||||
void ConfigVehicleTypeWidget::refreshWidgetsValues(UAVObject *)
|
||||
{
|
||||
if(!allObjectsUpdated())
|
||||
return;
|
||||
|
@ -76,7 +76,7 @@ private:
|
||||
UAVObject::Metadata accInitialData;
|
||||
|
||||
private slots:
|
||||
virtual void refreshWidgetsValues();
|
||||
virtual void refreshWidgetsValues(UAVObject * obj = NULL);
|
||||
void refreshFixedWingWidgetsValues(QString frameType);
|
||||
void refreshMultiRotorWidgetsValues(QString frameType);
|
||||
void refreshGroundVehicleWidgetsValues(QString frameType);
|
||||
|
@ -37,7 +37,7 @@ inputChannelForm::inputChannelForm(QWidget *parent,bool showlegend) :
|
||||
connect(ui->channelNumberDropdown,SIGNAL(currentIndexChanged(int)),this,SLOT(channelDropdownUpdated(int)));
|
||||
connect(ui->channelNumber,SIGNAL(valueChanged(int)),this,SLOT(channelNumberUpdated(int)));
|
||||
|
||||
disbleMouseWheelEvents();
|
||||
disableMouseWheelEvents();
|
||||
}
|
||||
|
||||
|
||||
|
@ -71,7 +71,7 @@ OutputChannelForm::OutputChannelForm(const int index, QWidget *parent, const boo
|
||||
connect(ui.actuatorLink, SIGNAL(toggled(bool)),
|
||||
this, SLOT(linkToggled(bool)));
|
||||
|
||||
disbleMouseWheelEvents();
|
||||
disableMouseWheelEvents();
|
||||
}
|
||||
|
||||
OutputChannelForm::~OutputChannelForm()
|
||||
|
1321
ground/openpilotgcs/src/plugins/config/pipxtreme.ui
Normal file
1321
ground/openpilotgcs/src/plugins/config/pipxtreme.ui
Normal file
@ -0,0 +1,1321 @@
|
||||
<?xml version="1.0" encoding="UTF-8"?>
|
||||
<ui version="4.0">
|
||||
<class>PipXtremeWidget</class>
|
||||
<widget class="QWidget" name="PipXtremeWidget">
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>0</x>
|
||||
<y>0</y>
|
||||
<width>840</width>
|
||||
<height>834</height>
|
||||
</rect>
|
||||
</property>
|
||||
<property name="windowTitle">
|
||||
<string>Form</string>
|
||||
</property>
|
||||
<layout class="QVBoxLayout" name="verticalLayout_3">
|
||||
<item>
|
||||
<widget class="QFrame" name="frame_3">
|
||||
<property name="frameShape">
|
||||
<enum>QFrame::StyledPanel</enum>
|
||||
</property>
|
||||
<property name="frameShadow">
|
||||
<enum>QFrame::Raised</enum>
|
||||
</property>
|
||||
<layout class="QGridLayout" name="gridLayout">
|
||||
<item row="0" column="0">
|
||||
<widget class="QFrame" name="frame_2">
|
||||
<property name="frameShape">
|
||||
<enum>QFrame::StyledPanel</enum>
|
||||
</property>
|
||||
<property name="frameShadow">
|
||||
<enum>QFrame::Raised</enum>
|
||||
</property>
|
||||
<layout class="QVBoxLayout" name="verticalLayout_2">
|
||||
<item>
|
||||
<widget class="QGroupBox" name="groupBox_2">
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>75</weight>
|
||||
<bold>true</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="title">
|
||||
<string>Pairing</string>
|
||||
</property>
|
||||
<layout class="QGridLayout" name="gridLayout_3">
|
||||
<item row="0" column="0">
|
||||
<widget class="QRadioButton" name="PairSelect1">
|
||||
<property name="text">
|
||||
<string/>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="1" colspan="2">
|
||||
<widget class="QLineEdit" name="PairID1"/>
|
||||
</item>
|
||||
<item row="0" column="3">
|
||||
<widget class="QProgressBar" name="PairSignalStrength1">
|
||||
<property name="minimum">
|
||||
<number>-127</number>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="value">
|
||||
<number>-127</number>
|
||||
</property>
|
||||
<property name="textVisible">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="format">
|
||||
<string>%v dBm</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="0">
|
||||
<widget class="QRadioButton" name="PairSelect2">
|
||||
<property name="text">
|
||||
<string/>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="1" colspan="2">
|
||||
<widget class="QLineEdit" name="PairID2"/>
|
||||
</item>
|
||||
<item row="1" column="3">
|
||||
<widget class="QProgressBar" name="PairSignalStrength2">
|
||||
<property name="minimum">
|
||||
<number>-127</number>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="value">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="textVisible">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="format">
|
||||
<string>%v dBm</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="0">
|
||||
<widget class="QRadioButton" name="PairSelect3">
|
||||
<property name="text">
|
||||
<string/>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="1" colspan="2">
|
||||
<widget class="QLineEdit" name="PairID3"/>
|
||||
</item>
|
||||
<item row="2" column="3">
|
||||
<widget class="QProgressBar" name="PairSignalStrength3">
|
||||
<property name="minimum">
|
||||
<number>-127</number>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="value">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="textVisible">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="format">
|
||||
<string>%v dBm</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="0">
|
||||
<widget class="QRadioButton" name="PairSelect4">
|
||||
<property name="text">
|
||||
<string/>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="1" colspan="2">
|
||||
<widget class="QLineEdit" name="PairID4"/>
|
||||
</item>
|
||||
<item row="3" column="3">
|
||||
<widget class="QProgressBar" name="PairSignalStrength4">
|
||||
<property name="minimum">
|
||||
<number>-127</number>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="value">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="textVisible">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="format">
|
||||
<string>%v dBm</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QGroupBox" name="groupBox_3">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>400</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>75</weight>
|
||||
<bold>true</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="title">
|
||||
<string>Status</string>
|
||||
</property>
|
||||
<layout class="QGridLayout" name="gridLayout_4">
|
||||
<item row="0" column="0">
|
||||
<widget class="QLabel" name="label_9">
|
||||
<property name="text">
|
||||
<string>Firmware Version</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="1">
|
||||
<widget class="QLineEdit" name="FirmwareVersion">
|
||||
<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 8px;
|
||||
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="2" column="0">
|
||||
<widget class="QLabel" name="label_2">
|
||||
<property name="text">
|
||||
<string>Serial Number</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="1">
|
||||
<widget class="QLineEdit" name="SerialNumber">
|
||||
<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="font">
|
||||
<font>
|
||||
<weight>75</weight>
|
||||
<italic>false</italic>
|
||||
<bold>true</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="acceptDrops">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>The modems serial number</string>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">QLineEdit {
|
||||
border: none;
|
||||
border-radius: 1px;
|
||||
padding: 0 8px;
|
||||
background: rgba(0, 0, 0, 16);
|
||||
/* background: transparent; */
|
||||
/* selection-background-color: darkgray;*/
|
||||
}</string>
|
||||
</property>
|
||||
<property name="frame">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
<property name="readOnly">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="4" column="0">
|
||||
<widget class="QLabel" name="label_3">
|
||||
<property name="text">
|
||||
<string>Min Frequency</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="4" column="1">
|
||||
<widget class="QLineEdit" name="MinFrequency">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>16777215</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>75</weight>
|
||||
<bold>true</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>The modems minimum allowed frequency</string>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">QLineEdit {
|
||||
border: none;
|
||||
border-radius: 1px;
|
||||
padding: 0 8px;
|
||||
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="0">
|
||||
<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="5" column="1">
|
||||
<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>16777215</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 8px;
|
||||
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="0">
|
||||
<widget class="QLabel" name="label_12">
|
||||
<property name="text">
|
||||
<string>Freq. Step Size</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="6" column="1">
|
||||
<widget class="QLineEdit" name="FrequencyStepSize">
|
||||
<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="font">
|
||||
<font>
|
||||
<weight>75</weight>
|
||||
<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;
|
||||
border-radius: 1px;
|
||||
padding: 0 8px;
|
||||
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="0">
|
||||
<widget class="QLabel" name="label_11">
|
||||
<property name="text">
|
||||
<string>Link State</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="7" column="1">
|
||||
<widget class="QLineEdit" name="LinkState">
|
||||
<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="font">
|
||||
<font>
|
||||
<weight>75</weight>
|
||||
<bold>true</bold>
|
||||
</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 8px;
|
||||
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="0">
|
||||
<widget class="QLabel" name="label_17">
|
||||
<property name="text">
|
||||
<string>Rx AFC</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="RxAFC">
|
||||
<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 8px;
|
||||
background: rgba(0, 0, 0, 16);
|
||||
/* background: transparent; */
|
||||
/* selection-background-color: darkgray;*/
|
||||
}</string>
|
||||
</property>
|
||||
<property name="readOnly">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="9" column="0">
|
||||
<widget class="QLabel" name="label_18">
|
||||
<property name="text">
|
||||
<string>Retries</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">
|
||||
<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 8px;
|
||||
background: rgba(0, 0, 0, 16);
|
||||
/* background: transparent; */
|
||||
/* selection-background-color: darkgray;*/
|
||||
}</string>
|
||||
</property>
|
||||
<property name="frame">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="readOnly">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="10" column="1">
|
||||
<widget class="QLineEdit" name="Errors">
|
||||
<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 8px;
|
||||
background: rgba(0, 0, 0, 16);
|
||||
/* background: transparent; */
|
||||
/* selection-background-color: darkgray;*/
|
||||
}</string>
|
||||
</property>
|
||||
<property name="frame">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="readOnly">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="10" column="0">
|
||||
<widget class="QLabel" name="label_19">
|
||||
<property name="text">
|
||||
<string>Errors</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="11" column="0">
|
||||
<widget class="QLabel" name="UAVTalkErrorsLabel">
|
||||
<property name="text">
|
||||
<string>UAVTalk Errors</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="11" column="1">
|
||||
<widget class="QLineEdit" name="UAVTalkErrors">
|
||||
<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 8px;
|
||||
background: rgba(0, 0, 0, 16);
|
||||
/* background: transparent; */
|
||||
/* selection-background-color: darkgray;*/
|
||||
}</string>
|
||||
</property>
|
||||
<property name="frame">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="readOnly">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="12" column="0">
|
||||
<widget class="QLabel" name="ResetsLabel">
|
||||
<property name="text">
|
||||
<string>Resets</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="12" column="1">
|
||||
<widget class="QLineEdit" name="Resets">
|
||||
<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 8px;
|
||||
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="13" column="0">
|
||||
<widget class="QLabel" name="TXRateLabel">
|
||||
<property name="text">
|
||||
<string>TX Rate (B/s)</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="13" column="1">
|
||||
<widget class="QLineEdit" name="TXRate">
|
||||
<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 8px;
|
||||
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="14" column="0">
|
||||
<widget class="QLabel" name="RXRateLabel">
|
||||
<property name="text">
|
||||
<string>RX Rate (B/s)</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="14" column="1">
|
||||
<widget class="QLineEdit" name="RXRate">
|
||||
<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 8px;
|
||||
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="3" column="1">
|
||||
<widget class="QLineEdit" name="DeviceID">
|
||||
<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 8px;
|
||||
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="3" column="0">
|
||||
<widget class="QLabel" name="label_20">
|
||||
<property name="text">
|
||||
<string>Device ID</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="1">
|
||||
<widget class="QGroupBox" name="groupBox">
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>75</weight>
|
||||
<bold>true</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="title">
|
||||
<string>Configuration</string>
|
||||
</property>
|
||||
<layout class="QGridLayout" name="gridLayout_2">
|
||||
<item row="0" column="0">
|
||||
<widget class="QLabel" name="TelemPortConfigLabel">
|
||||
<property name="text">
|
||||
<string>Telemetry Port Config.</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">
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>16777215</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Set the telemetry port configuration</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="0">
|
||||
<widget class="QLabel" name="TelemPortSpeedLabel">
|
||||
<property name="text">
|
||||
<string>Telemetry Port Speed</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">
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>16777215</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Set the telemetry port speed</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="0">
|
||||
<widget class="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>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="7" column="1">
|
||||
<widget class="QComboBox" name="MaxRFTxPower">
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>16777215</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Set the maximum TX output power the modem will use</string>
|
||||
</property>
|
||||
<property name="layoutDirection">
|
||||
<enum>Qt::LeftToRight</enum>
|
||||
</property>
|
||||
<property name="modelColumn">
|
||||
<number>0</number>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="8" column="0">
|
||||
<widget class="QLabel" name="SendTimeoutLabel">
|
||||
<property name="text">
|
||||
<string>Send Timeout (ms)</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="8" column="1">
|
||||
<widget class="QSpinBox" name="SendTimeout">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>16777215</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Calibrate the modems RF carrier frequency</string>
|
||||
</property>
|
||||
<property name="accelerated">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<number>255</number>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="9" column="0">
|
||||
<widget class="QLabel" name="MinPacketSizeLabel">
|
||||
<property name="text">
|
||||
<string>Min Packet Size</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="9" column="1">
|
||||
<widget class="QSpinBox" name="MinPacketSize">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>16777215</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Calibrate the modems RF carrier frequency</string>
|
||||
</property>
|
||||
<property name="accelerated">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<number>255</number>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="10" column="0">
|
||||
<widget class="QLabel" name="FreqCalLabel">
|
||||
<property name="text">
|
||||
<string>Frequency Calibration</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="10" column="1">
|
||||
<widget class="QSpinBox" name="FrequencyCalibration">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>16777215</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Calibrate the modems RF carrier frequency</string>
|
||||
</property>
|
||||
<property name="accelerated">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<number>255</number>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="11" column="0">
|
||||
<widget class="QLabel" name="label_5">
|
||||
<property name="text">
|
||||
<string>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">
|
||||
<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 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>0</number>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<number>1000000000</number>
|
||||
</property>
|
||||
<property name="singleStep">
|
||||
<number>100000</number>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="15" column="0" colspan="2">
|
||||
<widget class="QGroupBox" name="groupBox_4">
|
||||
<property name="title">
|
||||
<string>AES Encription</string>
|
||||
</property>
|
||||
<layout class="QGridLayout" name="gridLayout_5">
|
||||
<item row="0" column="0" colspan="2">
|
||||
<widget class="QLineEdit" name="AESKey">
|
||||
<property name="font">
|
||||
<font>
|
||||
<family>Courier New</family>
|
||||
<pointsize>9</pointsize>
|
||||
</font>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>The AES encryption key - has to be the same key on the remote modem.</string>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true"/>
|
||||
</property>
|
||||
<property name="maxLength">
|
||||
<number>32</number>
|
||||
</property>
|
||||
<property name="frame">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="0">
|
||||
<widget class="QPushButton" name="AESKeyRandom">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Fixed" vsizetype="Fixed">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Radomise the AES encryption key</string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string> Rand</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="1">
|
||||
<widget class="QCheckBox" name="AESEnable">
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>75</weight>
|
||||
<bold>true</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Enable/Disable AES encryption</string>
|
||||
</property>
|
||||
<property name="layoutDirection">
|
||||
<enum>Qt::RightToLeft</enum>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Enable</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="16" column="0">
|
||||
<spacer name="verticalSpacer">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Vertical</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>20</width>
|
||||
<height>40</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
<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>
|
||||
<item row="1" column="0" colspan="2">
|
||||
<layout class="QHBoxLayout" name="horizontalLayout_12">
|
||||
<item>
|
||||
<widget class="QGraphicsView" name="graphicsView_Spectrum">
|
||||
<property name="backgroundBrush">
|
||||
<brush brushstyle="NoBrush">
|
||||
<color alpha="255">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</property>
|
||||
<property name="foregroundBrush">
|
||||
<brush brushstyle="NoBrush">
|
||||
<color alpha="255">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</property>
|
||||
<property name="interactive">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
<item row="2" column="0" colspan="2">
|
||||
<layout class="QVBoxLayout" name="verticalLayout">
|
||||
<item>
|
||||
<widget class="QLabel" name="message">
|
||||
<property name="text">
|
||||
<string/>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<layout class="QHBoxLayout" name="submitButtons">
|
||||
<item>
|
||||
<widget class="QFrame" name="frame">
|
||||
<property name="frameShape">
|
||||
<enum>QFrame::StyledPanel</enum>
|
||||
</property>
|
||||
<property name="frameShadow">
|
||||
<enum>QFrame::Raised</enum>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<spacer name="horizontalSpacer">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>40</width>
|
||||
<height>20</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QPushButton" name="Apply">
|
||||
<property name="toolTip">
|
||||
<string>Send settings to the board but do not save to the non-volatile memory</string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Apply</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QPushButton" name="Save">
|
||||
<property name="toolTip">
|
||||
<string>Send settings to the board and save to the non-volatile memory</string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Save</string>
|
||||
</property>
|
||||
<property name="checked">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
</layout>
|
||||
<zorder>frame_2</zorder>
|
||||
<zorder>groupBox</zorder>
|
||||
<zorder>layoutWidget</zorder>
|
||||
<zorder>layoutWidget_2</zorder>
|
||||
<zorder>graphicsView_Spectrum</zorder>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
<resources/>
|
||||
<connections/>
|
||||
</ui>
|
@ -1734,6 +1734,7 @@
|
||||
<dataSize>60</dataSize>
|
||||
<plotCurve0>
|
||||
<color>4294901760</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>x</uavField>
|
||||
<uavObject>Accels</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
@ -1742,6 +1743,7 @@
|
||||
</plotCurve0>
|
||||
<plotCurve1>
|
||||
<color>4283782655</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>y</uavField>
|
||||
<uavObject>Accels</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
@ -1750,6 +1752,7 @@
|
||||
</plotCurve1>
|
||||
<plotCurve2>
|
||||
<color>4283804160</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>z</uavField>
|
||||
<uavObject>Accels</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
@ -1774,6 +1777,7 @@
|
||||
<dataSize>20</dataSize>
|
||||
<plotCurve0>
|
||||
<color>4294901760</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>Channel-4</uavField>
|
||||
<uavObject>ActuatorCommand</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
@ -1782,6 +1786,7 @@
|
||||
</plotCurve0>
|
||||
<plotCurve1>
|
||||
<color>4294901760</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>Channel-5</uavField>
|
||||
<uavObject>ActuatorCommand</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
@ -1790,6 +1795,7 @@
|
||||
</plotCurve1>
|
||||
<plotCurve2>
|
||||
<color>4289374847</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>Channel-6</uavField>
|
||||
<uavObject>ActuatorCommand</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
@ -1798,6 +1804,7 @@
|
||||
</plotCurve2>
|
||||
<plotCurve3>
|
||||
<color>4289374847</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>Channel-7</uavField>
|
||||
<uavObject>ActuatorCommand</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
@ -1822,6 +1829,7 @@
|
||||
<dataSize>60</dataSize>
|
||||
<plotCurve0>
|
||||
<color>4283760895</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>Roll</uavField>
|
||||
<uavObject>AttitudeActual</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
@ -1830,6 +1838,7 @@
|
||||
</plotCurve0>
|
||||
<plotCurve1>
|
||||
<color>4278233600</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>Yaw</uavField>
|
||||
<uavObject>AttitudeActual</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
@ -1838,6 +1847,7 @@
|
||||
</plotCurve1>
|
||||
<plotCurve2>
|
||||
<color>4294901760</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>Pitch</uavField>
|
||||
<uavObject>AttitudeActual</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
@ -1862,6 +1872,7 @@
|
||||
<dataSize>60</dataSize>
|
||||
<plotCurve0>
|
||||
<color>4278190080</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>Pressure</uavField>
|
||||
<uavObject>BaroAltitude</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
@ -1886,6 +1897,7 @@
|
||||
<dataSize>40</dataSize>
|
||||
<plotCurve0>
|
||||
<color>4278190207</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>Channel-1</uavField>
|
||||
<uavObject>ManualControlCommand</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
@ -1894,6 +1906,7 @@
|
||||
</plotCurve0>
|
||||
<plotCurve1>
|
||||
<color>4294901760</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>Channel-4</uavField>
|
||||
<uavObject>ManualControlCommand</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
@ -1902,6 +1915,7 @@
|
||||
</plotCurve1>
|
||||
<plotCurve2>
|
||||
<color>4294901760</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>Channel-5</uavField>
|
||||
<uavObject>ManualControlCommand</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
@ -1910,6 +1924,7 @@
|
||||
</plotCurve2>
|
||||
<plotCurve3>
|
||||
<color>4294901760</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>Channel-6</uavField>
|
||||
<uavObject>ManualControlCommand</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
@ -1918,6 +1933,7 @@
|
||||
</plotCurve3>
|
||||
<plotCurve4>
|
||||
<color>4294901760</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>Channel-7</uavField>
|
||||
<uavObject>ManualControlCommand</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
@ -1926,6 +1942,7 @@
|
||||
</plotCurve4>
|
||||
<plotCurve5>
|
||||
<color>4283825920</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>Channel-2</uavField>
|
||||
<uavObject>ManualControlCommand</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
@ -1934,6 +1951,7 @@
|
||||
</plotCurve5>
|
||||
<plotCurve6>
|
||||
<color>4294923520</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>Channel-3</uavField>
|
||||
<uavObject>ManualControlCommand</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
@ -1942,6 +1960,7 @@
|
||||
</plotCurve6>
|
||||
<plotCurve7>
|
||||
<color>4294967040</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>Channel-0</uavField>
|
||||
<uavObject>ManualControlCommand</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
@ -1966,6 +1985,7 @@
|
||||
<dataSize>60</dataSize>
|
||||
<plotCurve0>
|
||||
<color>4294901760</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>x</uavField>
|
||||
<uavObject>Accels</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
@ -1974,6 +1994,7 @@
|
||||
</plotCurve0>
|
||||
<plotCurve1>
|
||||
<color>4283782655</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>y</uavField>
|
||||
<uavObject>Accels</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
@ -1982,6 +2003,7 @@
|
||||
</plotCurve1>
|
||||
<plotCurve2>
|
||||
<color>4283804160</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>z</uavField>
|
||||
<uavObject>Accels</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
@ -2006,6 +2028,7 @@
|
||||
<dataSize>60</dataSize>
|
||||
<plotCurve0>
|
||||
<color>4283804160</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>z</uavField>
|
||||
<uavObject>Gyros</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
@ -2014,6 +2037,7 @@
|
||||
</plotCurve0>
|
||||
<plotCurve1>
|
||||
<color>4283782655</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>y</uavField>
|
||||
<uavObject>Gyros</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
@ -2022,6 +2046,7 @@
|
||||
</plotCurve1>
|
||||
<plotCurve2>
|
||||
<color>4294901760</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>x</uavField>
|
||||
<uavObject>Gyros</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
@ -2046,6 +2071,7 @@
|
||||
<dataSize>60</dataSize>
|
||||
<plotCurve0>
|
||||
<color>4294901760</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>X</uavField>
|
||||
<uavObject>Magnetometer</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
@ -2054,6 +2080,7 @@
|
||||
</plotCurve0>
|
||||
<plotCurve1>
|
||||
<color>4283782655</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>Y</uavField>
|
||||
<uavObject>Magnetometer</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
@ -2062,6 +2089,7 @@
|
||||
</plotCurve1>
|
||||
<plotCurve2>
|
||||
<color>4283804160</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>Z</uavField>
|
||||
<uavObject>Magnetometer</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
@ -2086,6 +2114,7 @@
|
||||
<dataSize>240</dataSize>
|
||||
<plotCurve0>
|
||||
<color>4294945280</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>StackRemaining-System</uavField>
|
||||
<uavObject>TaskInfo</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
@ -2094,6 +2123,7 @@
|
||||
</plotCurve0>
|
||||
<plotCurve1>
|
||||
<color>4294945280</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>StackRemaining-Actuator</uavField>
|
||||
<uavObject>TaskInfo</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
@ -2102,6 +2132,7 @@
|
||||
</plotCurve1>
|
||||
<plotCurve10>
|
||||
<color>4294945280</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>StackRemaining-Guidance</uavField>
|
||||
<uavObject>TaskInfo</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
@ -2110,6 +2141,7 @@
|
||||
</plotCurve10>
|
||||
<plotCurve11>
|
||||
<color>4294945280</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>StackRemaining-Watchdog</uavField>
|
||||
<uavObject>TaskInfo</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
@ -2118,6 +2150,7 @@
|
||||
</plotCurve11>
|
||||
<plotCurve2>
|
||||
<color>4294945280</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>StackRemaining-TelemetryTx</uavField>
|
||||
<uavObject>TaskInfo</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
@ -2126,6 +2159,7 @@
|
||||
</plotCurve2>
|
||||
<plotCurve3>
|
||||
<color>4294945280</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>StackRemaining-TelemetryTxPri</uavField>
|
||||
<uavObject>TaskInfo</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
@ -2134,6 +2168,7 @@
|
||||
</plotCurve3>
|
||||
<plotCurve4>
|
||||
<color>4294945280</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>StackRemaining-TelemetryRx</uavField>
|
||||
<uavObject>TaskInfo</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
@ -2142,6 +2177,7 @@
|
||||
</plotCurve4>
|
||||
<plotCurve5>
|
||||
<color>4294945280</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>StackRemaining-GPS</uavField>
|
||||
<uavObject>TaskInfo</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
@ -2150,6 +2186,7 @@
|
||||
</plotCurve5>
|
||||
<plotCurve6>
|
||||
<color>4294945280</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>StackRemaining-ManualControl</uavField>
|
||||
<uavObject>TaskInfo</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
@ -2158,6 +2195,7 @@
|
||||
</plotCurve6>
|
||||
<plotCurve7>
|
||||
<color>4294945280</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>StackRemaining-Altitude</uavField>
|
||||
<uavObject>TaskInfo</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
@ -2166,6 +2204,7 @@
|
||||
</plotCurve7>
|
||||
<plotCurve8>
|
||||
<color>4294945280</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>StackRemaining-AHRSComms</uavField>
|
||||
<uavObject>TaskInfo</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
@ -2174,6 +2213,7 @@
|
||||
</plotCurve8>
|
||||
<plotCurve9>
|
||||
<color>4294945280</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>StackRemaining-Stabilization</uavField>
|
||||
<uavObject>TaskInfo</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
@ -2198,6 +2238,7 @@
|
||||
<dataSize>20</dataSize>
|
||||
<plotCurve0>
|
||||
<color>4289374847</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>TxFailures</uavField>
|
||||
<uavObject>GCSTelemetryStats</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
@ -2206,6 +2247,7 @@
|
||||
</plotCurve0>
|
||||
<plotCurve1>
|
||||
<color>4283782655</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>RxFailures</uavField>
|
||||
<uavObject>GCSTelemetryStats</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
@ -2214,6 +2256,7 @@
|
||||
</plotCurve1>
|
||||
<plotCurve2>
|
||||
<color>4294901760</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>TxRetries</uavField>
|
||||
<uavObject>GCSTelemetryStats</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
@ -2238,6 +2281,7 @@
|
||||
<dataSize>240</dataSize>
|
||||
<plotCurve0>
|
||||
<color>4294945407</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>FlightTime</uavField>
|
||||
<uavObject>SystemStats</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
|
@ -308,13 +308,7 @@ void FGSimulator::processUpdate(const QByteArray& inp)
|
||||
double ECEF[3];
|
||||
double RNE[9];
|
||||
Utils::CoordinateConversions().RneFromLLA(LLA,(double (*)[3])RNE);
|
||||
for (int t=0;t<9;t++) {
|
||||
homeData.RNE[t]=RNE[t];
|
||||
}
|
||||
Utils::CoordinateConversions().LLA2ECEF(LLA,ECEF);
|
||||
homeData.ECEF[0]=ECEF[0]*100;
|
||||
homeData.ECEF[1]=ECEF[1]*100;
|
||||
homeData.ECEF[2]=ECEF[2]*100;
|
||||
homeData.Be[0]=0;
|
||||
homeData.Be[1]=0;
|
||||
homeData.Be[2]=0;
|
||||
@ -335,7 +329,7 @@ void FGSimulator::processUpdate(const QByteArray& inp)
|
||||
memset(&positionActualData, 0, sizeof(PositionActual::DataFields));
|
||||
positionActualData.North = 0; //Currently hardcoded as there is no way of setting up a reference point to calculate distance
|
||||
positionActualData.East = 0; //Currently hardcoded as there is no way of setting up a reference point to calculate distance
|
||||
positionActualData.Down = (altitude * 100); //Multiply by 100 because positionActual expects input in Centimeters.
|
||||
positionActualData.Down = altitude ; //Multiply by 1 because positionActual expects input in meters.
|
||||
posActual->setData(positionActualData);
|
||||
|
||||
// Update AltitudeActual object
|
||||
@ -371,26 +365,39 @@ void FGSimulator::processUpdate(const QByteArray& inp)
|
||||
gpsPos->setData(gpsData);
|
||||
|
||||
float NED[3];
|
||||
double LLA[3] = {(double) gpsData.Latitude / 1e7, (double) gpsData.Longitude / 1e7, (double) (gpsData.GeoidSeparation + gpsData.Altitude)};
|
||||
// convert from cm back to meters
|
||||
double ECEF[3] = {(double) (homeData.ECEF[0] / 100), (double) (homeData.ECEF[1] / 100), (double) (homeData.ECEF[2] / 100)};
|
||||
Utils::CoordinateConversions().LLA2Base(LLA, ECEF, (float (*)[3]) homeData.RNE, NED);
|
||||
|
||||
positionActualData.North = NED[0]*100; //Currently hardcoded as there is no way of setting up a reference point to calculate distance
|
||||
positionActualData.East = NED[1]*100; //Currently hardcoded as there is no way of setting up a reference point to calculate distance
|
||||
positionActualData.Down = NED[2]*100; //Multiply by 100 because positionActual expects input in Centimeters.
|
||||
double hLLA[3] = {(double) homeData.Latitude / 1e7, (double) homeData.Longitude / 1e7, (double) (homeData.Altitude)};
|
||||
double ECEF[3];
|
||||
double RNE[9];
|
||||
Utils::CoordinateConversions().RneFromLLA(hLLA,(double (*)[3])RNE);
|
||||
Utils::CoordinateConversions().LLA2ECEF(hLLA,ECEF);
|
||||
Utils::CoordinateConversions().LLA2Base(hLLA, ECEF, (float (*)[3]) RNE, NED);
|
||||
|
||||
positionActualData.North = NED[0]; //Currently hardcoded as there is no way of setting up a reference point to calculate distance
|
||||
positionActualData.East = NED[1]; //Currently hardcoded as there is no way of setting up a reference point to calculate distance
|
||||
positionActualData.Down = NED[2]; //Multiply by 1 because positionActual expects input in meters.
|
||||
posActual->setData(positionActualData);
|
||||
|
||||
// Update AttitudeRaw object (filtered gyros only for now)
|
||||
AttitudeRaw::DataFields rawData;
|
||||
memset(&rawData, 0, sizeof(AttitudeRaw::DataFields));
|
||||
rawData = attRaw->getData();
|
||||
rawData.gyros[0] = rollRate;
|
||||
//AttitudeRaw::DataFields rawData;
|
||||
//AttitudeRaw::DataFields rawData;
|
||||
Gyros::DataFields gyroData;
|
||||
Accels::DataFields accelData;
|
||||
memset(&gyroData, 0, sizeof(Gyros::DataFields));
|
||||
memset(&accelData, 0, sizeof(Accels::DataFields));
|
||||
gyroData = gyros->getData();
|
||||
accelData = accels->getData();
|
||||
//rawData.gyros[0] = rollRate;
|
||||
//rawData.gyros[1] = cos(DEG2RAD * roll) * pitchRate + sin(DEG2RAD * roll) * yawRate;
|
||||
//rawData.gyros[2] = cos(DEG2RAD * roll) * yawRate - sin(DEG2RAD * roll) * pitchRate;
|
||||
rawData.gyros[1] = pitchRate;
|
||||
rawData.gyros[2] = yawRate;
|
||||
attRaw->setData(rawData);
|
||||
//rawData.gyros[1] = pitchRate;
|
||||
//rawData.gyros[2] = yawRate;
|
||||
gyroData.x = rollRate;
|
||||
gyroData.y = pitchRate;
|
||||
gyroData.z = yawRate;
|
||||
// TODO: Accels are still missing!!!!
|
||||
gyros->setData(gyroData);
|
||||
// attRaw->updated();
|
||||
}
|
||||
|
||||
|
@ -263,35 +263,45 @@ void IL2Simulator::processUpdate(const QByteArray& inp)
|
||||
// Update positionActual objects
|
||||
PositionActual::DataFields posData;
|
||||
memset(&posData, 0, sizeof(PositionActual::DataFields));
|
||||
posData.North = current.Y*100;
|
||||
posData.East = current.X*100;
|
||||
posData.Down = current.Z*-100;
|
||||
posData.North = current.Y;
|
||||
posData.East = current.X;
|
||||
posData.Down = current.Z*-1.;
|
||||
|
||||
// Update velocityActual objects
|
||||
VelocityActual::DataFields velData;
|
||||
memset(&velData, 0, sizeof(VelocityActual::DataFields));
|
||||
velData.North = current.dY*100;
|
||||
velData.East = current.dX*100;
|
||||
velData.Down = current.dZ*-100;
|
||||
velData.North = current.dY;
|
||||
velData.East = current.dX;
|
||||
velData.Down = current.dZ*-1.;
|
||||
|
||||
// Update AttitudeRaw object (filtered gyros and accels only for now)
|
||||
AttitudeRaw::DataFields rawData;
|
||||
memset(&rawData, 0, sizeof(AttitudeRaw::DataFields));
|
||||
rawData = attRaw->getData();
|
||||
//AttitudeRaw::DataFields rawData;
|
||||
//memset(&rawData, 0, sizeof(AttitudeRaw::DataFields));
|
||||
//rawData = attRaw->getData();
|
||||
Gyros::DataFields gyroData;
|
||||
Accels::DataFields accelData;
|
||||
memset(&gyroData, 0, sizeof(Gyros::DataFields));
|
||||
memset(&accelData, 0, sizeof(Accels::DataFields));
|
||||
gyroData = gyros->getData();
|
||||
accelData = accels->getData();
|
||||
|
||||
// rotate turn rates and accelerations into body frame
|
||||
// (note: rotation deltas are NOT in NED frame but in RPY - manual conversion!)
|
||||
rawData.gyros[0] = current.dRoll;
|
||||
rawData.gyros[1] = cos(DEG2RAD * current.roll) * current.dPitch + sin(DEG2RAD * current.roll) * current.dAzimuth;
|
||||
rawData.gyros[2] = cos(DEG2RAD * current.roll) * current.dAzimuth - sin(DEG2RAD * current.roll) * current.dPitch;
|
||||
gyroData.x = current.dRoll;
|
||||
gyroData.y = cos(DEG2RAD * current.roll) * current.dPitch + sin(DEG2RAD * current.roll) * current.dAzimuth;
|
||||
gyroData.z = cos(DEG2RAD * current.roll) * current.dAzimuth - sin(DEG2RAD * current.roll) * current.dPitch;
|
||||
// accels are in NED and can be converted using standard ned->local rotation matrix
|
||||
float Rbe[3][3];
|
||||
Utils::CoordinateConversions().Quaternion2R(quat,Rbe);
|
||||
for (int t=0;t<3;t++) {
|
||||
rawData.accels[t]=current.ddX*Rbe[t][0]
|
||||
+current.ddY*Rbe[t][1]
|
||||
+(current.ddZ+GEE)*Rbe[t][2];
|
||||
}
|
||||
rawData.accels[2]=-rawData.accels[2];
|
||||
accelData.x = current.ddX*Rbe[0][0]
|
||||
+current.ddY*Rbe[0][1]
|
||||
+(current.ddZ+GEE)*Rbe[0][2];
|
||||
accelData.y = current.ddX*Rbe[1][0]
|
||||
+current.ddY*Rbe[1][1]
|
||||
+(current.ddZ+GEE)*Rbe[1][2];
|
||||
accelData.z = - (current.ddX*Rbe[2][0]
|
||||
+current.ddY*Rbe[2][1]
|
||||
+(current.ddZ+GEE)*Rbe[2][2]);
|
||||
|
||||
// Update homelocation
|
||||
HomeLocation::DataFields homeData;
|
||||
@ -307,13 +317,7 @@ void IL2Simulator::processUpdate(const QByteArray& inp)
|
||||
double ECEF[3];
|
||||
double RNE[9];
|
||||
Utils::CoordinateConversions().RneFromLLA(LLA,(double (*)[3])RNE);
|
||||
for (int t=0;t<9;t++) {
|
||||
homeData.RNE[t]=RNE[t];
|
||||
}
|
||||
Utils::CoordinateConversions().LLA2ECEF(LLA,ECEF);
|
||||
homeData.ECEF[0]=ECEF[0]*100;
|
||||
homeData.ECEF[1]=ECEF[1]*100;
|
||||
homeData.ECEF[2]=ECEF[2]*100;
|
||||
homeData.Be[0]=0;
|
||||
homeData.Be[1]=0;
|
||||
homeData.Be[2]=0;
|
||||
@ -339,7 +343,9 @@ void IL2Simulator::processUpdate(const QByteArray& inp)
|
||||
// update every time (50ms)
|
||||
attActual->setData(attActualData);
|
||||
//attActual->updated();
|
||||
attRaw->setData(rawData);
|
||||
//attRaw->setData(rawData);
|
||||
gyros->setData(gyroData);
|
||||
accels->setData(accelData);
|
||||
//attRaw->updated();
|
||||
velActual->setData(velData);
|
||||
//velActual->updated();
|
||||
|
@ -49,7 +49,7 @@ Simulator::Simulator(const SimulatorSettings& params) :
|
||||
outSocket(NULL),
|
||||
settings(params),
|
||||
updatePeriod(50),
|
||||
simTimeout(2000),
|
||||
simTimeout(8000),
|
||||
autopilotConnectionStatus(false),
|
||||
simConnectionStatus(false),
|
||||
txTimer(NULL),
|
||||
@ -131,7 +131,8 @@ void Simulator::onStart()
|
||||
posActual = PositionActual::GetInstance(objManager);
|
||||
altActual = BaroAltitude::GetInstance(objManager);
|
||||
attActual = AttitudeActual::GetInstance(objManager);
|
||||
attRaw = AttitudeRaw::GetInstance(objManager);
|
||||
accels = Accels::GetInstance(objManager);
|
||||
gyros = Gyros::GetInstance(objManager);
|
||||
gpsPos = GPSPosition::GetInstance(objManager);
|
||||
telStats = GCSTelemetryStats::GetInstance(objManager);
|
||||
|
||||
@ -225,7 +226,8 @@ void Simulator::setupObjects()
|
||||
setupOutputObject(posActual, 250);
|
||||
setupOutputObject(velActual, 250);
|
||||
setupOutputObject(posHome, 1000);
|
||||
setupOutputObject(attRaw, 10);
|
||||
setupOutputObject(accels, 10);
|
||||
setupOutputObject(gyros, 10);
|
||||
//setupOutputObject(attRaw, 100);
|
||||
|
||||
|
||||
|
Some files were not shown because too many files have changed in this diff Show More
Loading…
x
Reference in New Issue
Block a user