AP_Radio: implement CYRF6936 direct attached radio

implement DSM2 and DSMX compatible protocols
This commit is contained in:
Andrew Tridgell 2017-03-10 10:37:58 +11:00
parent b9e5649888
commit be002665cf
9 changed files with 2568 additions and 0 deletions

View File

@ -0,0 +1,242 @@
#include <AP_HAL/AP_HAL.h>
#ifdef HAL_RCINPUT_WITH_AP_RADIO
#include "AP_Radio.h"
#include "AP_Radio_backend.h"
#include "AP_Radio_cypress.h"
extern const AP_HAL::HAL& hal;
// table of user settable parameters
const AP_Param::GroupInfo AP_Radio::var_info[] = {
// @Param: _TYPE
// @DisplayName: Set type of direct attached radio
// @Description: This enables support for direct attached radio receivers
// @Values: 0:None,1:CYRF6936
// @User: Advanced
AP_GROUPINFO("_TYPE", 1, AP_Radio, radio_type, 0),
// @Param: _PROT
// @DisplayName: protocol
// @Description: Select air protocol
// @Values: 0:Auto,1:DSM2,2:DSMX
// @User: Advanced
AP_GROUPINFO("_PROT", 2, AP_Radio, protocol, PROTOCOL_AUTO),
// @Param: _DEBUG
// @DisplayName: debug level
// @Description: radio debug level
// @Range: 0 4
// @User: Advanced
AP_GROUPINFO("_DEBUG", 3, AP_Radio, debug_level, 0),
// @Param: _DISCRC
// @DisplayName: disable receive CRC
// @Description: disable receive CRC (for debug)
// @Values: 0:NotDisabled,1:Disabled
// @User: Advanced
AP_GROUPINFO("_DISCRC", 4, AP_Radio, disable_crc, 0),
// @Param: _SIGCH
// @DisplayName: RSSI signal strength
// @Description: Channel to show receive RSSI signal strength, or zero for disabled
// @Range: 0 16
// @User: Advanced
AP_GROUPINFO("_SIGCH", 5, AP_Radio, rssi_chan, 0),
// @Param: _PPSCH
// @DisplayName: Packet rate channel
// @Description: Channel to show received packet-per-second rate, or zero for disabled
// @Range: 0 16
// @User: Advanced
AP_GROUPINFO("_PPSCH", 6, AP_Radio, pps_chan, 0),
// @Param: _TELEM
// @DisplayName: Enable telemetry
// @Description: If this is non-zero then telemetry packets will be sent over DSM
// @Values: 0:Disabled,1:Enabled
// @User: Advanced
AP_GROUPINFO("_TELEM", 7, AP_Radio, telem_enable, 0),
// @Param: _TXPOW
// @DisplayName: Telemetry Transmit power
// @Description: Set telemetry transmit power. This is the power level (from 1 to 8) for telemetry packets sent from the RX to the TX
// @Range: 1 8
// @User: Advanced
AP_GROUPINFO("_TXPOW", 8, AP_Radio, transmit_power, 8),
// @Param: _FCCTST
// @DisplayName: Put radio into FCC test mode
// @Description: If this is enabled then the radio will continuously transmit as required for FCC testing. The transmit channel is set by the value of the parameter. The radio will not work for RC input while this is enabled
// @Values: 0:Disabled,1:MinChannel,2:MidChannel,3:MaxChannel,4:MinChannelCW,5:MidChannelCW,6:MaxChannelCW
// @User: Advanced
AP_GROUPINFO("_FCCTST", 9, AP_Radio, fcc_test, 0),
// @Param: _STKMD
// @DisplayName: Stick input mode
// @Description: This selects between different stick input modes. The default is mode2, which has throttle on the left stick and pitch on the right stick. You can instead set mode1, which has throttle on the right stick and pitch on the left stick.
// @Values: 1:Mode1,2:Mode2
// @User: Advanced
AP_GROUPINFO("_STKMD", 10, AP_Radio, stick_mode, 2),
// @Param: _TESTCH
// @DisplayName: Set radio to factory test channel
// @Description: This sets the radio to a fixed test channel for factory testing. Using a fixed channel avoids the need for binding in factory testing.
// @Values: 0:Disabled,1:TestChan1,2:TestChan2,3:TestChan3,4:TestChan4,5:TestChan5,6:TestChan6,7:TestChan7,8:TestChan8
// @User: Advanced
AP_GROUPINFO("_TESTCH", 11, AP_Radio, factory_test, 0),
// @Param: _TSIGCH
// @DisplayName: RSSI value channel for telemetry data on transmitter
// @Description: Channel to show telemetry RSSI value as received by TX
// @Range: 0 16
// @User: Advanced
AP_GROUPINFO("_TSIGCH", 12, AP_Radio, tx_rssi_chan, 0),
// @Param: _TPPSCH
// @DisplayName: Telemetry PPS channel
// @Description: Channel to show telemetry packets-per-second value, as received at TX
// @Range: 0 16
// @User: Advanced
AP_GROUPINFO("_TPPSCH", 13, AP_Radio, tx_pps_chan, 0),
// @Param: _TXMAX
// @DisplayName: Transmitter transmit power
// @Description: Set transmitter maximum transmit power (from 1 to 8)
// @Range: 1 8
// @User: Advanced
AP_GROUPINFO("_TXMAX", 14, AP_Radio, tx_max_power, 4),
// @Param: _BZOFS
// @DisplayName: Transmitter buzzer adjustment
// @Description: Set transmitter buzzer note adjustment (adjust frequency up)
// @Range: 0 40
// @User: Advanced
AP_GROUPINFO("_BZOFS", 15, AP_Radio, tx_buzzer_adjust, 25),
// @Param: _ABTIME
// @DisplayName: Auto-bind time
// @Description: When non-zero this sets the time with no transmitter packets before we start looking for auto-bind packets.
// @Range: 0 120
// @User: Advanced
AP_GROUPINFO("_ABTIME", 16, AP_Radio, auto_bind_time, 0),
// @Param: _ABLVL
// @DisplayName: Auto-bind level
// @Description: This sets the minimum RSSI of an auto-bind packet for it to be accepted. This should be set so that auto-bind will only happen at short range to minimise the change of an auto-bind happening accidentially
// @Range: 0 31
// @User: Advanced
AP_GROUPINFO("_ABLVL", 17, AP_Radio, auto_bind_rssi, 0),
AP_GROUPEND
};
AP_Radio *AP_Radio::_instance;
// constructor
AP_Radio::AP_Radio(void)
{
AP_Param::setup_object_defaults(this, var_info);
if (_instance != nullptr) {
AP_HAL::panic("Multiple AP_Radio declarations");
}
_instance = this;
}
bool AP_Radio::init(void)
{
switch (radio_type) {
case RADIO_TYPE_CYRF6936:
driver = new AP_Radio_cypress(*this);
break;
default:
break;
}
if (!driver) {
return false;
}
return driver->init();
}
bool AP_Radio::reset(void)
{
if (!driver) {
return false;
}
return driver->reset();
}
bool AP_Radio::send(const uint8_t *pkt, uint16_t len)
{
if (!driver) {
return false;
}
return driver->send(pkt, len);
}
void AP_Radio::start_recv_bind(void)
{
if (!driver) {
return;
}
return driver->start_recv_bind();
}
const AP_Radio::stats &AP_Radio::get_stats(void)
{
return driver->get_stats();
}
uint8_t AP_Radio::num_channels(void)
{
if (!driver) {
return 0;
}
return driver->num_channels();
}
uint16_t AP_Radio::read(uint8_t chan)
{
if (!driver) {
return 0;
}
return driver->read(chan);
}
uint32_t AP_Radio::last_recv_us(void)
{
if (!driver) {
return 0;
}
return driver->last_recv_us();
}
// update status, should be called from main thread
void AP_Radio::update(void)
{
if (driver) {
driver->update();
}
}
// get transmitter firmware version
uint32_t AP_Radio::get_tx_version(void)
{
if (driver) {
return driver->get_tx_version();
}
return 0;
}
// set the 2.4GHz wifi channel used by companion computer, so it can be avoided
void AP_Radio::set_wifi_channel(uint8_t channel)
{
if (driver) {
driver->set_wifi_channel(channel);
}
}
#endif // HAL_RCINPUT_WITH_AP_RADIO

View File

@ -0,0 +1,116 @@
/*
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/>.
*/
#pragma once
/*
* base class for direct attached radios
*/
#include <AP_HAL/AP_HAL.h>
#include <AP_Param/AP_Param.h>
#include <GCS_MAVLink/GCS.h>
class AP_Radio_backend;
class AP_Radio
{
public:
friend class AP_Radio_backend;
// constructor
AP_Radio(void);
// init - initialise radio
bool init(void);
// reset the radio
bool reset(void);
// send a packet
bool send(const uint8_t *pkt, uint16_t len);
// start bind process as a receiver
void start_recv_bind(void);
// return time in microseconds of last received R/C packet
uint32_t last_recv_us(void);
// return number of input channels
uint8_t num_channels(void);
// return current PWM of a channel
uint16_t read(uint8_t chan);
// update status, should be called from main thread
void update(void);
// get transmitter firmware version
uint32_t get_tx_version(void);
struct stats {
uint32_t bad_packets;
uint32_t recv_errors;
uint32_t recv_packets;
uint32_t lost_packets;
uint32_t timeouts;
};
enum ap_radio_type {
RADIO_TYPE_NONE=0,
RADIO_TYPE_CYRF6936=1,
};
enum ap_radio_protocol {
PROTOCOL_AUTO=0,
PROTOCOL_DSM2=1,
PROTOCOL_DSMX=2,
};
// get packet statistics
const struct stats &get_stats(void);
static const struct AP_Param::GroupInfo var_info[];
// get singleton instance
static AP_Radio *instance(void) {
return _instance;
}
// set the 2.4GHz wifi channel used by companion computer, so it can be avoided
void set_wifi_channel(uint8_t channel);
private:
AP_Radio_backend *driver;
AP_Int8 radio_type;
AP_Int8 protocol;
AP_Int8 debug_level;
AP_Int8 disable_crc;
AP_Int8 rssi_chan;
AP_Int8 pps_chan;
AP_Int8 tx_rssi_chan;
AP_Int8 tx_pps_chan;
AP_Int8 telem_enable;
AP_Int8 transmit_power;
AP_Int8 tx_max_power;
AP_Int8 fcc_test;
AP_Int8 stick_mode;
AP_Int8 factory_test;
AP_Int8 tx_buzzer_adjust;
AP_Int8 auto_bind_time;
AP_Int8 auto_bind_rssi;
static AP_Radio *_instance;
};

View File

@ -0,0 +1,29 @@
/*
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/>.
*/
/*
* backend class for direct attached radios
*/
#include <AP_HAL/AP_HAL.h>
#include "AP_Radio_backend.h"
AP_Radio_backend::AP_Radio_backend(AP_Radio &_radio) :
radio(_radio)
{
}
AP_Radio_backend::~AP_Radio_backend(void)
{
}

View File

@ -0,0 +1,134 @@
/*
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/>.
*/
#pragma once
/*
* backend class for direct attached radios
*/
#include <AP_HAL/AP_HAL.h>
#include "AP_Radio.h"
class AP_Radio_backend
{
public:
AP_Radio_backend(AP_Radio &radio);
virtual ~AP_Radio_backend();
// init - initialise radio
virtual bool init(void) = 0;
// init - reset radio
virtual bool reset(void) = 0;
// send a packet
virtual bool send(const uint8_t *pkt, uint16_t len) = 0;
// start bind process as a receiver
virtual void start_recv_bind(void) = 0;
// return time in microseconds of last received R/C packet
virtual uint32_t last_recv_us(void) = 0;
// return number of input channels
virtual uint8_t num_channels(void) = 0;
// return current PWM of a channel
virtual uint16_t read(uint8_t chan) = 0;
// update status
virtual void update(void) = 0;
// get TX fw version
virtual uint32_t get_tx_version(void) = 0;
// get radio statistics structure
virtual const AP_Radio::stats &get_stats(void) = 0;
// set the 2.4GHz wifi channel used by companion computer, so it can be avoided
virtual void set_wifi_channel(uint8_t channel) = 0;
protected:
AP_Radio::ap_radio_protocol get_protocol(void) const {
return (AP_Radio::ap_radio_protocol)radio.protocol.get();
}
uint8_t get_debug_level(void) const {
return (uint8_t)radio.debug_level.get();
}
bool get_disable_crc(void) const {
return (bool)radio.disable_crc.get();
}
uint8_t get_rssi_chan(void) const {
return (uint8_t)radio.rssi_chan.get();
}
uint8_t get_pps_chan(void) const {
return (uint8_t)radio.pps_chan.get();
}
uint8_t get_tx_rssi_chan(void) const {
return (uint8_t)radio.tx_rssi_chan.get();
}
uint8_t get_tx_pps_chan(void) const {
return (uint8_t)radio.tx_pps_chan.get();
}
bool get_telem_enable(void) const {
return radio.telem_enable.get() > 0;
}
uint8_t get_transmit_power(void) const {
return constrain_int16(radio.transmit_power.get(), 1, 8);
}
uint8_t get_tx_max_power(void) const {
return constrain_int16(radio.tx_max_power.get(), 1, 8);
}
void set_tx_max_power_default(uint8_t v) {
return radio.tx_max_power.set_default(v);
}
int8_t get_fcc_test(void) const {
return radio.fcc_test.get();
}
uint8_t get_stick_mode(void) const {
return radio.stick_mode.get();
}
uint8_t get_factory_test(void) const {
return radio.factory_test.get();
}
uint8_t get_tx_buzzer_adjust(void) const {
return radio.tx_buzzer_adjust.get();
}
uint8_t get_autobind_time(void) const {
return radio.auto_bind_time.get();
}
uint8_t get_autobind_rssi(void) const {
return radio.auto_bind_rssi.get();
}
AP_Radio &radio;
};

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,278 @@
/*
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/>.
*/
#pragma once
/*
AP_Radio implementation for Cypress 2.4GHz radio.
With thanks to the SuperBitRF project
See http://wiki.paparazziuav.org/wiki/SuperbitRF
This implementation uses the DSMX protocol on a CYRF6936
*/
#include "AP_Radio_backend.h"
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
#include <nuttx/arch.h>
#include <systemlib/systemlib.h>
#include <drivers/drv_hrt.h>
#endif
#include "telem_structure.h"
class AP_Radio_cypress : public AP_Radio_backend
{
public:
AP_Radio_cypress(AP_Radio &radio);
// init - initialise radio
bool init(void) override;
// rest radio
bool reset(void) override;
// send a packet
bool send(const uint8_t *pkt, uint16_t len) override;
// start bind process as a receiver
void start_recv_bind(void) override;
// return time in microseconds of last received R/C packet
uint32_t last_recv_us(void) override;
// return number of input channels
uint8_t num_channels(void) override;
// return current PWM of a channel
uint16_t read(uint8_t chan) override;
// update status
void update(void) override;
// get TX fw version
uint32_t get_tx_version(void) override {
// pack date into 16 bits for vendor_id in AUTOPILOT_VERSION
return (uint16_t(dsm.tx_firmware_year)<<12) + (uint16_t(dsm.tx_firmware_month)<<8) + dsm.tx_firmware_day;
}
// get radio statistics structure
const AP_Radio::stats &get_stats(void) override;
// set the 2.4GHz wifi channel used by companion computer, so it can be avoided
void set_wifi_channel(uint8_t channel) {
t_status.wifi_chan = channel;
}
private:
AP_HAL::OwnPtr<AP_HAL::SPIDevice> dev;
static AP_Radio_cypress *radio_instance;
void radio_init(void);
void dump_registers(uint8_t n);
bool force_initial_state(void);
void set_channel(uint8_t channel);
uint8_t read_status_debounced(uint8_t adr);
uint8_t read_register(uint8_t reg);
void write_register(uint8_t reg, uint8_t value);
void write_multiple(uint8_t reg, uint8_t n, const uint8_t *data);
enum {
STATE_RECV,
STATE_BIND,
STATE_AUTOBIND,
STATE_SEND_TELEM,
STATE_SEND_TELEM_WAIT,
STATE_SEND_FCC
} state;
struct config {
uint8_t reg;
uint8_t value;
};
static const uint8_t pn_codes[5][9][8];
static const uint8_t pn_bind[];
static const config cyrf_config[];
static const config cyrf_bind_config[];
static const config cyrf_transfer_config[];
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
sem_t irq_sem;
struct hrt_call wait_call;
#endif
void radio_set_config(const struct config *config, uint8_t size);
void start_receive(void);
// main IRQ handler
void irq_handler(void);
// IRQ handler for packet receive
void irq_handler_recv(uint8_t rx_status);
// handle timeout IRQ
void irq_timeout(void);
// trampoline functions to take us from static IRQ function to class functions
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
static int irq_radio_trampoline(int irq, void *context);
static int irq_timeout_trampoline(int irq, void *context);
#endif
static const uint8_t max_channels = 16;
uint32_t last_debug_print_ms;
void print_debug_info(void);
AP_Radio::stats stats;
AP_Radio::stats last_stats;
enum dsm_protocol {
DSM_NONE = 0, // not bound yet
DSM_DSM2_1 = 0x01, // The original DSM2 protocol with 1 packet of data
DSM_DSM2_2 = 0x02, // The original DSM2 protocol with 2 packets of data
DSM_DSMX_1 = 0xA2, // The original DSMX protocol with 1 packet of data
DSM_DSMX_2 = 0xB2, // The original DSMX protocol with 2 packets of data
};
enum dsm2_sync {
DSM2_SYNC_A,
DSM2_SYNC_B,
DSM2_OK
};
// semaphore between ISR and main thread
AP_HAL::Semaphore *sem;
// dsm config data and status
struct {
uint8_t channels[23];
enum dsm_protocol protocol;
uint8_t mfg_id[4];
uint8_t current_channel;
uint8_t current_rf_channel;
uint16_t crc_seed;
uint8_t sop_col;
uint8_t data_col;
uint8_t last_sop_code[8];
uint8_t last_data_code[16];
uint32_t receive_start_us;
uint32_t receive_timeout_usec;
uint32_t last_recv_us;
uint32_t last_parse_us;
uint32_t last_recv_chan;
uint32_t last_chan_change_us;
uint16_t num_channels;
uint16_t pwm_channels[max_channels];
bool need_bind_save;
enum dsm2_sync sync;
uint32_t crc_errors;
float rssi;
bool last_discrc;
uint8_t last_transmit_power;
uint32_t send_irq_count;
uint32_t send_count;
uint16_t pkt_time1 = 3000;
uint16_t pkt_time2 = 7000;
uint8_t tx_firmware_year;
uint8_t tx_firmware_month;
uint8_t tx_firmware_day;
int8_t forced_channel = -1;
uint8_t tx_rssi;
uint8_t tx_pps;
uint32_t last_autobind_send;
bool have_tx_pps;
uint32_t telem_send_count;
uint8_t tx_bl_version;
} dsm;
struct {
mavlink_channel_t chan;
bool need_ack;
uint8_t counter;
uint8_t sequence;
uint32_t offset;
uint32_t length;
uint32_t acked;
uint8_t len;
enum telem_type fw_type;
uint8_t pending_data[92];
} fwupload;
// bind structure saved to storage
static const uint16_t bind_magic = 0x43F6;
struct PACKED bind_info {
uint16_t magic;
uint8_t mfg_id[4];
enum dsm_protocol protocol;
};
struct telem_status t_status;
// DSM specific functions
void dsm_set_channel(uint8_t channel, bool is_dsm2, uint8_t sop_col, uint8_t data_col, uint16_t crc_seed);
// generate DSMX channels
void dsm_generate_channels_dsmx(uint8_t mfg_id[4], uint8_t channels[23]);
// setup for DSMX transfers
void dsm_setup_transfer_dsmx(void);
// choose channel to receive on
void dsm_choose_channel(void);
// map for mode1/mode2
void map_stick_mode(uint16_t *channels);
// parse DSM channels from a packet
bool parse_dsm_channels(const uint8_t *data);
// process an incoming packet
void process_packet(const uint8_t *pkt, uint8_t len);
// process an incoming bind packet
void process_bind(const uint8_t *pkt, uint8_t len);
// load bind info from storage
void load_bind_info(void);
// save bind info to storage
void save_bind_info(void);
bool is_DSM2(void);
// send a 16 byte packet
void transmit16(const uint8_t data[16]);
void send_telem_packet(void);
void irq_handler_send(uint8_t tx_status);
void send_FCC_test_packet(void);
// check sending of fw upload ack
void check_fw_ack(void);
// re-sync DSM2
void dsm2_start_sync(void);
// check for double binding
void check_double_bind(void);
};

View File

@ -0,0 +1,49 @@
/*
* DSM receiver example code for Cypress radio
*
* With thanks to the SuperBitRF project and their excellent cyrf6936 dongle:
* https://1bitsquared.com/products/superbit-usbrf-dongle
*/
#include <AP_HAL/AP_HAL.h>
#include <AP_Radio/AP_Radio.h>
#include <stdio.h>
#define debug(fmt, args...) printf(fmt, ##args)
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
static AP_Radio radio;
static bool do_bind = false;
void setup()
{
hal.console->begin(115200);
debug("RADIO init\n");
hal.scheduler->delay(1000);
radio.init();
if (do_bind) {
radio.start_recv_bind();
}
}
void loop()
{
static AP_Radio::stats stats;
hal.scheduler->delay(1000);
AP_Radio::stats new_stats = radio.get_stats();
debug("recv:%3u bad:%3u to:%3u re:%u N:%2u 1:%4u 1:%4u 3:%4u 4:%4u 5:%4u 6:%4u 7:%4u 8:%4u 14:%u\n",
new_stats.recv_packets - stats.recv_packets,
new_stats.bad_packets - stats.bad_packets,
new_stats.timeouts - stats.timeouts,
new_stats.recv_errors - stats.recv_errors,
radio.num_channels(),
radio.read(0), radio.read(1), radio.read(2), radio.read(3),
radio.read(4), radio.read(5), radio.read(6), radio.read(7),
radio.read(13));
stats = new_stats;
}
AP_HAL_MAIN();

View File

@ -0,0 +1,7 @@
#!/usr/bin/env python
# encoding: utf-8
def build(bld):
bld.ap_example(
use='ap',
)

View File

@ -0,0 +1,74 @@
/*
structures for telemetry packets
This header is common to ArduPilot AP_Radio and STM8 TX code
*/
#pragma once
enum telem_type {
TELEM_STATUS= 0, // a telem_status packet
TELEM_PLAY = 1, // play a tune
TELEM_FW = 2, // update new firmware
};
#define TELEM_FLAG_GPS_OK (1U<<0)
#define TELEM_FLAG_ARM_OK (1U<<1)
#define TELEM_FLAG_BATT_OK (1U<<2)
#define TELEM_FLAG_ARMED (1U<<4)
#define TELEM_FLAG_POS_OK (1U<<5)
#define TELEM_FLAG_VIDEO (1U<<6)
#define TELEM_FLAG_HYBRID (1U<<7)
struct telem_status {
uint8_t pps; // packets per second received
uint8_t rssi; // lowpass rssi
uint8_t flags; // TELEM_FLAG_*
uint8_t flight_mode; // flight mode
uint8_t wifi_chan;
uint8_t tx_max;
uint8_t note_adjust;
};
// play a tune
struct telem_play {
uint8_t seq;
uint8_t tune_index;
};
// write to new firmware
struct telem_firmware {
uint8_t seq;
uint8_t len;
uint16_t offset;
uint8_t data[8];
};
/*
telemetry packet from RX to TX
*/
struct telem_packet {
uint8_t crc; // simple CRC
enum telem_type type;
union {
uint8_t pkt[14];
struct telem_status status;
struct telem_firmware fw;
} payload;
};
enum tx_telem_type {
TXTELEM_RSSI = 0,
TXTELEM_CRC1 = 1,
TXTELEM_CRC2 = 2,
};
/*
tx_status structure sent one byte at a time to RX. This is packed
into channels 8, 9 and 10 (using 32 bits of a possible 33)
*/
struct telem_tx_status {
uint8_t crc;
enum tx_telem_type type;
uint16_t data;
};