mirror of https://github.com/ArduPilot/ardupilot
AP_RCProtocol: SRXL2 support
This commit is contained in:
parent
967f8bf726
commit
68c6a3b03d
|
@ -22,6 +22,7 @@
|
|||
#include "AP_RCProtocol_SBUS.h"
|
||||
#include "AP_RCProtocol_SUMD.h"
|
||||
#include "AP_RCProtocol_SRXL.h"
|
||||
#include "AP_RCProtocol_SRXL2.h"
|
||||
#include "AP_RCProtocol_ST24.h"
|
||||
#include "AP_RCProtocol_FPort.h"
|
||||
#include <AP_Math/AP_Math.h>
|
||||
|
@ -37,6 +38,7 @@ void AP_RCProtocol::init()
|
|||
backend[AP_RCProtocol::DSM] = new AP_RCProtocol_DSM(*this);
|
||||
backend[AP_RCProtocol::SUMD] = new AP_RCProtocol_SUMD(*this);
|
||||
backend[AP_RCProtocol::SRXL] = new AP_RCProtocol_SRXL(*this);
|
||||
backend[AP_RCProtocol::SRXL2] = new AP_RCProtocol_SRXL2(*this);
|
||||
backend[AP_RCProtocol::ST24] = new AP_RCProtocol_ST24(*this);
|
||||
backend[AP_RCProtocol::FPORT] = new AP_RCProtocol_FPort(*this, true);
|
||||
}
|
||||
|
@ -308,6 +310,8 @@ const char *AP_RCProtocol::protocol_name_from_protocol(rcprotocol_t protocol)
|
|||
return "SUMD";
|
||||
case SRXL:
|
||||
return "SRXL";
|
||||
case SRXL2:
|
||||
return "SRXL2";
|
||||
case ST24:
|
||||
return "ST24";
|
||||
case FPORT:
|
||||
|
|
|
@ -37,6 +37,7 @@ public:
|
|||
DSM,
|
||||
SUMD,
|
||||
SRXL,
|
||||
SRXL2,
|
||||
ST24,
|
||||
FPORT,
|
||||
NONE //last enum always is None
|
||||
|
|
|
@ -70,11 +70,11 @@ public:
|
|||
|
||||
protected:
|
||||
void add_input(uint8_t num_channels, uint16_t *values, bool in_failsafe, int16_t rssi=-1);
|
||||
AP_RCProtocol &frontend;
|
||||
|
||||
void log_data(AP_RCProtocol::rcprotocol_t prot, uint32_t timestamp, const uint8_t *data, uint8_t len) const;
|
||||
|
||||
private:
|
||||
AP_RCProtocol &frontend;
|
||||
uint32_t rc_input_count;
|
||||
uint32_t last_rc_input_count;
|
||||
uint32_t rc_frame_count;
|
||||
|
|
|
@ -0,0 +1,309 @@
|
|||
/*
|
||||
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/>.
|
||||
*/
|
||||
/*
|
||||
SRXL2 protocol decoder using Horizon Hobby's open source library https://github.com/SpektrumRC/SRXL2
|
||||
Code by Andy Piper
|
||||
*/
|
||||
|
||||
#include "spm_srxl.h"
|
||||
|
||||
#include "AP_RCProtocol.h"
|
||||
#include "AP_RCProtocol_SRXL.h"
|
||||
#include "AP_RCProtocol_SRXL2.h"
|
||||
#include <AP_Math/AP_Math.h>
|
||||
#include <AP_Spektrum_Telem/AP_Spektrum_Telem.h>
|
||||
#include <AP_Vehicle/AP_Vehicle_Type.h>
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
//#define SRXL2_DEBUG
|
||||
#ifdef SRXL2_DEBUG
|
||||
# define debug(fmt, args...) hal.console->printf("SRXL2:" fmt "\n", ##args)
|
||||
#else
|
||||
# define debug(fmt, args...) do {} while(0)
|
||||
#endif
|
||||
|
||||
AP_RCProtocol_SRXL2* AP_RCProtocol_SRXL2::_singleton;
|
||||
|
||||
AP_RCProtocol_SRXL2::AP_RCProtocol_SRXL2(AP_RCProtocol &_frontend) : AP_RCProtocol_Backend(_frontend)
|
||||
{
|
||||
const uint32_t uniqueID = AP_HAL::micros();
|
||||
|
||||
if (_singleton != nullptr) {
|
||||
AP_HAL::panic("Duplicate SRXL2 handler");
|
||||
}
|
||||
|
||||
_singleton = this;
|
||||
// Init the local SRXL device
|
||||
if (!srxlInitDevice(SRXL_DEVICE_ID, SRXL_DEVICE_PRIORITY, SRXL_DEVICE_INFO, uniqueID)) {
|
||||
AP_HAL::panic("Failed to initialize SRXL2 device");
|
||||
}
|
||||
|
||||
// Init the SRXL bus: The bus index must always be < SRXL_NUM_OF_BUSES -- in this case, it can only be 0
|
||||
if (!srxlInitBus(0, this, SRXL_SUPPORTED_BAUD_RATES)) {
|
||||
AP_HAL::panic("Failed to initialize SRXL2 bus");
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
void AP_RCProtocol_SRXL2::process_pulse(uint32_t width_s0, uint32_t width_s1)
|
||||
{
|
||||
uint8_t b;
|
||||
if (ss.process_pulse(width_s0, width_s1, b)) {
|
||||
_process_byte(ss.get_byte_timestamp_us(), b);
|
||||
}
|
||||
}
|
||||
|
||||
void AP_RCProtocol_SRXL2::_process_byte(uint32_t timestamp_us, uint8_t byte)
|
||||
{
|
||||
if (_decode_state == STATE_IDLE) {
|
||||
switch (byte) {
|
||||
case SPEKTRUM_SRXL_ID:
|
||||
_frame_len_full = 0U;
|
||||
_decode_state = STATE_NEW;
|
||||
break;
|
||||
default:
|
||||
_frame_len_full = 0U;
|
||||
_decode_state = STATE_IDLE;
|
||||
_buflen = 0;
|
||||
return;
|
||||
}
|
||||
}
|
||||
|
||||
switch (_decode_state) {
|
||||
case STATE_NEW: // buffer header byte and prepare for frame reception and decoding
|
||||
_buffer[0U]=byte;
|
||||
_buflen = 1U;
|
||||
_decode_state_next = STATE_COLLECT;
|
||||
break;
|
||||
|
||||
case STATE_COLLECT: // receive all bytes. After reception decode frame and provide rc channel information to FMU
|
||||
_buffer[_buflen] = byte;
|
||||
_buflen++;
|
||||
|
||||
// need a header to get the length
|
||||
if (_buflen < SRXL2_HEADER_LEN) {
|
||||
return;
|
||||
}
|
||||
|
||||
// parse the length
|
||||
if (_buflen == SRXL2_HEADER_LEN) {
|
||||
_frame_len_full = _buffer[2];
|
||||
return;
|
||||
}
|
||||
|
||||
if (_buflen > _frame_len_full) {
|
||||
// a logic bug in the state machine, this shouldn't happen
|
||||
_decode_state = STATE_IDLE;
|
||||
_buflen = 0;
|
||||
_frame_len_full = 0;
|
||||
return;
|
||||
}
|
||||
|
||||
if (_buflen == _frame_len_full) {
|
||||
log_data(AP_RCProtocol::SRXL2, timestamp_us, _buffer, _buflen);
|
||||
// Try to parse SRXL packet -- this internally calls srxlRun() after packet is parsed and resets timeout
|
||||
if (srxlParsePacket(0, _buffer, _frame_len_full)) {
|
||||
add_input(MAX_CHANNELS, _channels, _in_failsafe, _new_rssi);
|
||||
}
|
||||
_last_run_ms = AP_HAL::millis();
|
||||
_decode_state_next = STATE_IDLE;
|
||||
} else {
|
||||
_decode_state_next = STATE_COLLECT;
|
||||
}
|
||||
break;
|
||||
|
||||
default:
|
||||
break;
|
||||
}
|
||||
|
||||
_decode_state = _decode_state_next;
|
||||
_last_data_us = timestamp_us;
|
||||
}
|
||||
|
||||
void AP_RCProtocol_SRXL2::update(void)
|
||||
{
|
||||
#if 0 // it's not clear this is actually required
|
||||
if (frontend.protocol_detected() == AP_RCProtocol::SRXL2) {
|
||||
uint32_t now = AP_HAL::millis();
|
||||
// there have been no updates since we were last called
|
||||
const uint32_t delay = now - _last_run_ms;
|
||||
if (delay > 5) {
|
||||
srxlRun(0, delay);
|
||||
_last_run_ms = now;
|
||||
}
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
void AP_RCProtocol_SRXL2::capture_scaled_input(const uint16_t *values, bool in_failsafe, int16_t new_rssi)
|
||||
{
|
||||
AP_RCProtocol_SRXL2* srxl2 = AP_RCProtocol_SRXL2::get_singleton();
|
||||
|
||||
if (srxl2 != nullptr) {
|
||||
srxl2->_capture_scaled_input(values, in_failsafe, new_rssi);
|
||||
}
|
||||
}
|
||||
|
||||
// capture SRXL2 encoded values
|
||||
void AP_RCProtocol_SRXL2::_capture_scaled_input(const uint16_t *values, bool in_failsafe, int16_t new_rssi)
|
||||
{
|
||||
_in_failsafe = in_failsafe;
|
||||
// AP rssi: -1 for unknown, 0 for no link, 255 for maximum link
|
||||
// SRXL2 rssi: -ve rssi in dBM, +ve rssi in percentage
|
||||
if (new_rssi >= 0) {
|
||||
_new_rssi = new_rssi * 255 / 100;
|
||||
} else {
|
||||
// pretty much a guess
|
||||
_new_rssi = 255 - 255 * (-20 - new_rssi) / (-20 - 85);
|
||||
}
|
||||
|
||||
for (uint8_t i = 0; i < MAX_CHANNELS; i++) {
|
||||
/*
|
||||
* Each channel data value is sent as an unsigned 16-bit value from 0 to 65532 (0xFFFC)
|
||||
* with 32768 (0x8000) representing "Servo Center". The channel value must be bit-shifted
|
||||
* to the right to match the applications's accepted resolution.
|
||||
*
|
||||
* So here we scale to DSMX-2048 and then use our regular Spektrum conversion.
|
||||
*/
|
||||
_channels[i] = ((((int)(values[i] >> 5) - 1024) * 1000) / 1700) + 1500;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
// start bind on DSM satellites
|
||||
void AP_RCProtocol_SRXL2::start_bind(void)
|
||||
{
|
||||
srxlEnterBind(DSMX_11MS, true);
|
||||
}
|
||||
|
||||
// process a byte provided by a uart
|
||||
void AP_RCProtocol_SRXL2::process_byte(uint8_t byte, uint32_t baudrate)
|
||||
{
|
||||
if (baudrate != 115200) {
|
||||
return;
|
||||
}
|
||||
_process_byte(AP_HAL::micros(), byte);
|
||||
}
|
||||
|
||||
// send data to the uart
|
||||
void AP_RCProtocol_SRXL2::send_on_uart(uint8_t* pBuffer, uint8_t length)
|
||||
{
|
||||
AP_RCProtocol_SRXL2* srxl2 = AP_RCProtocol_SRXL2::get_singleton();
|
||||
|
||||
if (srxl2 != nullptr) {
|
||||
srxl2->_send_on_uart(pBuffer, length);
|
||||
}
|
||||
}
|
||||
|
||||
// send data to the uart
|
||||
void AP_RCProtocol_SRXL2::_send_on_uart(uint8_t* pBuffer, uint8_t length)
|
||||
{
|
||||
// writing at startup locks-up the flight controller
|
||||
if (have_UART() && AP_HAL::millis() > 3000) {
|
||||
// check that we haven't been too slow in responding to the new
|
||||
// UART data. If we respond too late then we will corrupt the next
|
||||
// incoming control frame
|
||||
uint64_t tend = get_UART()->receive_time_constraint_us(1);
|
||||
uint64_t now = AP_HAL::micros64();
|
||||
uint64_t tdelay = now - tend;
|
||||
if (tdelay > 2500) {
|
||||
// we've been too slow in responding
|
||||
return;
|
||||
}
|
||||
// debug telemetry packets
|
||||
if (pBuffer[1] == 0x80 && pBuffer[4] != 0) {
|
||||
debug("0x%x 0x%x 0x%x 0x%x 0x%x 0x%x 0x%x 0x%x 0x%x 0x%x: %s",
|
||||
pBuffer[0], pBuffer[1], pBuffer[2], pBuffer[3], pBuffer[4], pBuffer[5], pBuffer[6], pBuffer[7], pBuffer[8], pBuffer[9], &pBuffer[7]);
|
||||
}
|
||||
get_UART()->write(pBuffer, length);
|
||||
}
|
||||
}
|
||||
|
||||
// change the uart baud rate
|
||||
void AP_RCProtocol_SRXL2::change_baud_rate(uint32_t baudrate)
|
||||
{
|
||||
AP_RCProtocol_SRXL2* srxl2 = AP_RCProtocol_SRXL2::get_singleton();
|
||||
|
||||
if (srxl2 != nullptr) {
|
||||
srxl2->_change_baud_rate(baudrate);
|
||||
}
|
||||
}
|
||||
|
||||
// change the uart baud rate
|
||||
void AP_RCProtocol_SRXL2::_change_baud_rate(uint32_t baudrate)
|
||||
{
|
||||
#if 0
|
||||
if (have_UART()) {
|
||||
get_UART()->begin(baudrate);
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
// User-provided routine to change the baud rate settings on the given UART:
|
||||
// uart - the same uint8_t value as the uart parameter passed to srxlInit()
|
||||
// baudRate - the actual baud rate (currently either 115200 or 400000)
|
||||
void srxlChangeBaudRate(void* this_ptr, uint32_t baudRate)
|
||||
{
|
||||
AP_RCProtocol_SRXL2::change_baud_rate(baudRate);
|
||||
|
||||
}
|
||||
|
||||
// User-provided routine to actually transmit a packet on the given UART:
|
||||
// uart - the same uint8_t value as the uart parameter passed to srxlInit()
|
||||
// pBuffer - a pointer to an array of uint8_t values to send over the UART
|
||||
// length - the number of bytes contained in pBuffer that should be sent
|
||||
void srxlSendOnUart(void* this_ptr, uint8_t* pBuffer, uint8_t length)
|
||||
{
|
||||
AP_RCProtocol_SRXL2::send_on_uart(pBuffer, length);
|
||||
}
|
||||
|
||||
// User-provided callback routine to fill in the telemetry data to send to the master when requested:
|
||||
// pTelemetryData - a pointer to the 16-byte SrxlTelemetryData transmit buffer to populate
|
||||
// NOTE: srxlTelemData is available as a global variable, so the memcpy line commented out below
|
||||
// could be used if you would prefer to just populate that with the next outgoing telemetry packet.
|
||||
void srxlFillTelemetry(SrxlTelemetryData* pTelemetryData)
|
||||
{
|
||||
#if !APM_BUILD_TYPE(APM_BUILD_iofirmware)
|
||||
AP_Spektrum_Telem::get_telem_data(pTelemetryData->raw);
|
||||
#endif
|
||||
}
|
||||
|
||||
// User-provided callback routine that is called whenever a control data packet is received:
|
||||
// pChannelData - a pointer to the received SrxlChannelData structure for manual parsing
|
||||
// isFailsafe - true if channel data is set to failsafe values, else false.
|
||||
// this is called from within srxlParsePacket() and before the SRXL2 state machine has been run
|
||||
// so be very careful to only do local operations
|
||||
void srxlReceivedChannelData(SrxlChannelData* pChannelData, bool isFailsafe)
|
||||
{
|
||||
if (isFailsafe) {
|
||||
AP_RCProtocol_SRXL2::capture_scaled_input(pChannelData->values, true, pChannelData->rssi);
|
||||
} else {
|
||||
AP_RCProtocol_SRXL2::capture_scaled_input(srxlChData.values, false, srxlChData.rssi);
|
||||
}
|
||||
}
|
||||
|
||||
// User-provided callback routine to handle reception of a bound data report (either requested or unprompted).
|
||||
// Return true if you want this bind information set automatically for all other receivers on all SRXL buses.
|
||||
bool srxlOnBind(SrxlFullID device, SrxlBindData info)
|
||||
{
|
||||
// TODO: Add custom handling of bound data report here if needed
|
||||
return true;
|
||||
}
|
||||
|
||||
// User-provided callback routine to handle reception of a VTX control packet.
|
||||
void srxlOnVtx(SrxlVtxData* pVtxData)
|
||||
{
|
||||
//userProvidedHandleVtxData(pVtxData);
|
||||
}
|
|
@ -0,0 +1,72 @@
|
|||
/*
|
||||
* This file 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 file 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
|
||||
|
||||
#include "AP_RCProtocol.h"
|
||||
#include <AP_Math/AP_Math.h>
|
||||
#include "SoftSerial.h"
|
||||
|
||||
#define SRXL2_MAX_CHANNELS 32U /* Maximum number of channels from srxl2 datastream */
|
||||
#define SRXL2_FRAMELEN_MAX 80U /* maximum possible framelengh */
|
||||
#define SRXL2_HEADER_LEN 3U
|
||||
|
||||
class AP_RCProtocol_SRXL2 : public AP_RCProtocol_Backend {
|
||||
public:
|
||||
AP_RCProtocol_SRXL2(AP_RCProtocol &_frontend);
|
||||
void process_pulse(uint32_t width_s0, uint32_t width_s1) override;
|
||||
void process_byte(uint8_t byte, uint32_t baudrate) override;
|
||||
void start_bind(void) override;
|
||||
void update(void) override;
|
||||
// get singleton instance
|
||||
static AP_RCProtocol_SRXL2* get_singleton() {
|
||||
return _singleton;
|
||||
}
|
||||
|
||||
// static functions for SRXL2 callbacks
|
||||
static void capture_scaled_input(const uint16_t *values, bool in_failsafe, int16_t rssi);
|
||||
static void send_on_uart(uint8_t* pBuffer, uint8_t length);
|
||||
static void change_baud_rate(uint32_t baudrate);
|
||||
|
||||
private:
|
||||
|
||||
const uint8_t MAX_CHANNELS = MIN((uint8_t)SRXL_MAX_CHANNELS, (uint8_t)MAX_RCIN_CHANNELS);
|
||||
|
||||
static AP_RCProtocol_SRXL2* _singleton;
|
||||
|
||||
void _process_byte(uint32_t timestamp_us, uint8_t byte);
|
||||
void _send_on_uart(uint8_t* pBuffer, uint8_t length);
|
||||
void _change_baud_rate(uint32_t baudrate);
|
||||
void _capture_scaled_input(const uint16_t *values, bool in_failsafe, int16_t rssi);
|
||||
|
||||
uint8_t _buffer[SRXL2_FRAMELEN_MAX]; /* buffer for raw srxl frame data in correct order --> buffer[0]=byte0 buffer[1]=byte1 */
|
||||
uint8_t _buflen; /* length in number of bytes of received srxl dataframe in buffer */
|
||||
uint32_t _last_data_us; /* timespan since last received data in us */
|
||||
uint32_t _last_run_ms; // last time the state machine was run
|
||||
uint16_t _channels[SRXL2_MAX_CHANNELS] = {0}; /* buffer for extracted RC channel data as pulsewidth in microseconds */
|
||||
|
||||
enum {
|
||||
STATE_IDLE, /* do nothing */
|
||||
STATE_NEW, /* get header of frame + prepare for frame reception */
|
||||
STATE_COLLECT /* collect RC channel data from frame */
|
||||
};
|
||||
uint8_t _frame_len_full = 0U; /* Length in number of bytes of full srxl datastream */
|
||||
uint8_t _decode_state = STATE_IDLE; /* Current state of SRXL frame decoding */
|
||||
uint8_t _decode_state_next = STATE_IDLE; /* State of frame decoding that will be applied when the next byte from dataframe drops in */
|
||||
bool _in_failsafe = false;
|
||||
int16_t _new_rssi = -1;
|
||||
|
||||
SoftSerial ss{115200, SoftSerial::SERIAL_CONFIG_8N1};
|
||||
};
|
|
@ -26,6 +26,7 @@ void loop();
|
|||
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX || CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||
|
||||
#include <AP_RCProtocol/AP_RCProtocol.h>
|
||||
#include <RC_Channel/RC_Channel.h>
|
||||
#include <stdio.h>
|
||||
#include <sys/types.h>
|
||||
#include <sys/stat.h>
|
||||
|
@ -39,6 +40,29 @@ void loop();
|
|||
|
||||
static AP_RCProtocol *rcprot;
|
||||
|
||||
class RC_Channel_RC : public RC_Channel
|
||||
{
|
||||
};
|
||||
|
||||
class RC_Channels_RC : public RC_Channels
|
||||
{
|
||||
public:
|
||||
RC_Channel *channel(uint8_t chan) override {
|
||||
return &obj_channels[chan];
|
||||
}
|
||||
|
||||
RC_Channel_RC obj_channels[NUM_RC_CHANNELS];
|
||||
private:
|
||||
int8_t flight_mode_channel_number() const override { return -1; };
|
||||
};
|
||||
|
||||
#define RC_CHANNELS_SUBCLASS RC_Channels_RC
|
||||
#define RC_CHANNEL_SUBCLASS RC_Channel_RC
|
||||
|
||||
#include <RC_Channel/RC_Channels_VarInfo.h>
|
||||
|
||||
RC_Channels_RC _rc;
|
||||
|
||||
// change this to the device being tested.
|
||||
const char *devicename = "/dev/serial/by-id/usb-FTDI_FT232R_USB_UART_A10596TP-if00-port0";
|
||||
const uint32_t baudrate = 115200;
|
||||
|
|
File diff suppressed because it is too large
Load Diff
|
@ -0,0 +1,533 @@
|
|||
/*
|
||||
MIT License
|
||||
|
||||
Copyright (c) 2019 Horizon Hobby, LLC
|
||||
|
||||
Permission is hereby granted, free of charge, to any person obtaining a copy
|
||||
of this software and associated documentation files (the "Software"), to deal
|
||||
in the Software without restriction, including without limitation the rights
|
||||
to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
|
||||
copies of the Software, and to permit persons to whom the Software is
|
||||
furnished to do so, subject to the following conditions:
|
||||
|
||||
The above copyright notice and this permission notice shall be included in all
|
||||
copies or substantial portions of the Software.
|
||||
|
||||
THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
|
||||
IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
|
||||
FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
|
||||
AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
|
||||
LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
|
||||
OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
|
||||
SOFTWARE.
|
||||
*/
|
||||
|
||||
#ifndef __SRXL_H__
|
||||
#define __SRXL_H__
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C"
|
||||
{
|
||||
#endif
|
||||
|
||||
// Standard C Libraries
|
||||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
#include <stdlib.h>
|
||||
|
||||
|
||||
// 7.1 General Overview
|
||||
#define SPEKTRUM_SRXL_ID (0xA6)
|
||||
#define SRXL_MAX_BUFFER_SIZE (80)
|
||||
#define SRXL_MAX_DEVICES (16)
|
||||
|
||||
// Supported SRXL device types (upper nibble of device ID)
|
||||
typedef enum
|
||||
{
|
||||
SrxlDevType_None = 0,
|
||||
SrxlDevType_RemoteReceiver = 1,
|
||||
SrxlDevType_Receiver = 2,
|
||||
SrxlDevType_FlightController = 3,
|
||||
SrxlDevType_ESC = 4,
|
||||
SrxlDevType_SRXLServo1 = 6,
|
||||
SrxlDevType_SRXLServo2 = 7,
|
||||
SrxlDevType_VTX = 8,
|
||||
SrxlDevType_Broadcast = 15
|
||||
} SrxlDevType;
|
||||
|
||||
// Default device ID list used by master when polling
|
||||
static const uint8_t SRXL_DEFAULT_ID_OF_TYPE[16] =
|
||||
{
|
||||
[SrxlDevType_None] = 0x00,
|
||||
[SrxlDevType_RemoteReceiver] = 0x10,
|
||||
[SrxlDevType_Receiver] = 0x21,
|
||||
[SrxlDevType_FlightController] = 0x30,
|
||||
[SrxlDevType_ESC] = 0x40,
|
||||
[5] = 0x60,
|
||||
[SrxlDevType_SRXLServo1] = 0x60,
|
||||
[SrxlDevType_SRXLServo2] = 0x70,
|
||||
[SrxlDevType_VTX] = 0x81,
|
||||
[9] = 0xFF,
|
||||
[10] = 0xFF,
|
||||
[11] = 0xFF,
|
||||
[12] = 0xFF,
|
||||
[13] = 0xFF,
|
||||
[14] = 0xFF,
|
||||
[SrxlDevType_Broadcast] = 0xFF,
|
||||
};
|
||||
|
||||
// Set SRXL_CRC_OPTIMIZE_MODE in spm_srxl_config.h to one of the following values
|
||||
#define SRXL_CRC_OPTIMIZE_SPEED (1) // Uses table lookup for CRC computation (requires 512 const bytes for CRC table)
|
||||
#define SRXL_CRC_OPTIMIZE_SIZE (2) // Uses bitwise operations
|
||||
#define SRXL_CRC_OPTIMIZE_STM_HW (3) // Uses STM32 register-level hardware acceleration (only available on STM32F30x devices for now)
|
||||
#define SRXL_CRC_OPTIMIZE_STM_HAL (4) // Uses STM32Cube HAL driver for hardware acceleration (only available on STM32F3/F7) -- see srxlCrc16() for details on HAL config
|
||||
|
||||
// Set SRXL_STM_TARGET_FAMILY in spm_srxl_config.h to one of the following values when using one of the STM HW-optimized modes
|
||||
#define SRXL_STM_TARGET_F3 (3)
|
||||
#define SRXL_STM_TARGET_F7 (7)
|
||||
|
||||
// 7.2 Handshake Packet
|
||||
#define SRXL_HANDSHAKE_ID (0x21)
|
||||
|
||||
// Supported additional baud rates besides default 115200
|
||||
// NOTE: Treated as bitmask, ANDed with baud rates from slaves
|
||||
#define SRXL_BAUD_115200 (0x00)
|
||||
#define SRXL_BAUD_400000 (0x01)
|
||||
//#define SRXL_BAUD_NEXT_RATE (0x02)
|
||||
//#define SRXL_BAUD_ANOTHER (0x04)
|
||||
|
||||
// Bit masks for Device Info byte sent via Handshake
|
||||
#define SRXL_DEVINFO_NO_RF (0x00) // This is the base for non-RF devices
|
||||
#define SRXL_DEVINFO_TELEM_TX_ENABLED (0x01) // This bit is set if the device is actively configured to transmit telemetry over RF
|
||||
#define SRXL_DEVINFO_TELEM_FULL_RANGE (0x02) // This bit is set if the device can send full-range telemetry over RF
|
||||
#define SRXL_DEVINFO_FWD_PROG_SUPPORT (0x04) // This bit is set if the device supports Forward Programming via RF or SRXL
|
||||
|
||||
// 7.3 Bind Info Packet
|
||||
#define SRXL_BIND_ID (0x41)
|
||||
#define SRXL_BIND_REQ_ENTER (0xEB)
|
||||
#define SRXL_BIND_REQ_STATUS (0xB5)
|
||||
#define SRXL_BIND_REQ_BOUND_DATA (0xDB)
|
||||
#define SRXL_BIND_REQ_SET_BIND (0x5B)
|
||||
|
||||
// Bit masks for Options byte
|
||||
#define SRXL_BIND_OPT_NONE (0x00)
|
||||
#define SRXL_BIND_OPT_TELEM_TX_ENABLE (0x01) // Set if this device should be enabled as the current telemetry device to tx over RF
|
||||
#define SRXL_BIND_OPT_BIND_TX_ENABLE (0x02) // Set if this device should reply to a bind request with a Discover packet over RF
|
||||
#define SRXL_BIND_OPT_US_POWER (0x04) // Set if this device should request US transmit power levels instead of EU
|
||||
|
||||
// Current Bind Status
|
||||
typedef enum
|
||||
{
|
||||
NOT_BOUND = 0x00,
|
||||
// Air types
|
||||
DSM2_1024_22MS = 0x01,
|
||||
DSM2_1024_MC24 = 0x02,
|
||||
DSM2_2048_11MS = 0x12,
|
||||
DSMX_22MS = 0xA2,
|
||||
DSMX_11MS = 0xB2,
|
||||
// Surface types (corresponding Air type bitwise OR'd with 0x40)
|
||||
SURFACE_DSM1 = 0x40,
|
||||
SURFACE_DSM2_16p5MS = 0x63,
|
||||
DSMR_11MS_22MS = 0xE2,
|
||||
DSMR_5p5MS = 0xE4,
|
||||
} BIND_STATUS;
|
||||
|
||||
// 7.4 Parameter Configuration
|
||||
#define SRXL_PARAM_ID (0x50)
|
||||
#define SRXL_PARAM_REQ_QUERY (0x50)
|
||||
#define SRXL_PARAM_REQ_WRITE (0x57)
|
||||
|
||||
// 7.5 Signal Quality Packet
|
||||
#define SRXL_RSSI_ID (0x55)
|
||||
#define SRXL_RSSI_REQ_REQUEST (0x52)
|
||||
#define SRXL_RSSI_REQ_SEND (0x53)
|
||||
|
||||
// 7.6 Telemetry Sensor Data Packet
|
||||
#define SRXL_TELEM_ID (0x80)
|
||||
|
||||
// 7.7 Control Data Packet
|
||||
#define SRXL_CTRL_ID (0xCD)
|
||||
#define SRXL_CTRL_BASE_LENGTH (3 + 2 + 2) // header + cmd/replyID + crc
|
||||
#define SRXL_CTRL_CMD_CHANNEL (0x00)
|
||||
#define SRXL_CTRL_CMD_CHANNEL_FS (0x01)
|
||||
#define SRXL_CTRL_CMD_VTX (0x02)
|
||||
#define SRXL_CTRL_CMD_FWDPGM (0x03)
|
||||
|
||||
typedef enum
|
||||
{
|
||||
SRXL_CMD_NONE,
|
||||
SRXL_CMD_CHANNEL,
|
||||
SRXL_CMD_CHANNEL_FS,
|
||||
SRXL_CMD_VTX,
|
||||
SRXL_CMD_FWDPGM,
|
||||
SRXL_CMD_RSSI,
|
||||
SRXL_CMD_HANDSHAKE,
|
||||
SRXL_CMD_TELEMETRY,
|
||||
SRXL_CMD_ENTER_BIND,
|
||||
SRXL_CMD_REQ_BIND,
|
||||
SRXL_CMD_SET_BIND,
|
||||
SRXL_CMD_BIND_INFO,
|
||||
} SRXL_CMD;
|
||||
|
||||
// VTX Band
|
||||
#define VTX_BAND_FATSHARK (0)
|
||||
#define VTX_BAND_RACEBAND (1)
|
||||
#define VTX_BAND_E_BAND (2)
|
||||
#define VTX_BAND_B_BAND (3)
|
||||
#define VTX_BAND_A_BAND (4)
|
||||
|
||||
// VTX Pit Mode
|
||||
#define VTX_MODE_RACE (0)
|
||||
#define VTX_MODE_PIT (1)
|
||||
|
||||
// VTX Power
|
||||
#define VTX_POWER_OFF (0)
|
||||
#define VTX_POWER_1MW_14MW (1)
|
||||
#define VTX_POWER_15MW_25MW (2)
|
||||
#define VTX_POWER_26MW_99MW (3)
|
||||
#define VTX_POWER_100MW_299MW (4)
|
||||
#define VTX_POWER_300MW_600MW (5)
|
||||
#define VTX_POWER_601_PLUS (6)
|
||||
#define VTX_POWER_MANUAL (7)
|
||||
|
||||
// VTX Region
|
||||
#define VTX_REGION_US (0)
|
||||
#define VTX_REGION_EU (1)
|
||||
|
||||
// Forward Programming Pass-Thru
|
||||
#define FWD_PGM_MAX_DATA_SIZE (64)
|
||||
|
||||
|
||||
// Enable byte packing for all structs defined here!
|
||||
#ifdef PACKED
|
||||
#error "preprocessor definition PACKED is already defined -- this could be bad"
|
||||
#endif
|
||||
#ifdef __GNUC__
|
||||
#define PACKED __attribute__((packed))
|
||||
#else
|
||||
#pragma pack(push, 1)
|
||||
#define PACKED
|
||||
#endif
|
||||
|
||||
// Spektrum SRXL header
|
||||
typedef struct SrxlHeader
|
||||
{
|
||||
uint8_t srxlID; // Always 0xA6 for SRXL2
|
||||
uint8_t packetType;
|
||||
uint8_t length;
|
||||
} PACKED SrxlHeader;
|
||||
|
||||
// Handshake
|
||||
typedef struct SrxlHandshakeData
|
||||
{
|
||||
uint8_t srcDevID;
|
||||
uint8_t destDevID;
|
||||
uint8_t priority;
|
||||
uint8_t baudSupported; // 0 = 115200, 1 = 400000 (See SRXL_BAUD_xxx definitions above)
|
||||
uint8_t info; // See SRXL_DEVINFO_xxx definitions above for defined bits
|
||||
uint32_t uid; // Unique/random id to allow detection of two devices on bus with same deviceID
|
||||
} PACKED SrxlHandshakeData;
|
||||
|
||||
typedef struct SrxlHandshakePacket
|
||||
{
|
||||
SrxlHeader hdr;
|
||||
SrxlHandshakeData payload;
|
||||
uint16_t crc;
|
||||
} PACKED SrxlHandshakePacket;
|
||||
|
||||
// Bind
|
||||
typedef struct SrxlBindData
|
||||
{
|
||||
uint8_t type;
|
||||
uint8_t options;
|
||||
uint64_t guid;
|
||||
uint32_t uid;
|
||||
} PACKED SrxlBindData;
|
||||
|
||||
typedef struct SrxlBindPacket
|
||||
{
|
||||
SrxlHeader hdr;
|
||||
uint8_t request;
|
||||
uint8_t deviceID;
|
||||
SrxlBindData data;
|
||||
uint16_t crc;
|
||||
} PACKED SrxlBindPacket;
|
||||
|
||||
// Telemetry
|
||||
typedef struct SrxlTelemetryData
|
||||
{
|
||||
union
|
||||
{
|
||||
struct
|
||||
{
|
||||
uint8_t sensorID;
|
||||
uint8_t secondaryID;
|
||||
uint8_t data[14];
|
||||
};
|
||||
uint8_t raw[16];
|
||||
};
|
||||
} PACKED SrxlTelemetryData;
|
||||
|
||||
typedef struct SrxlTelemetryPacket
|
||||
{
|
||||
SrxlHeader hdr;
|
||||
uint8_t destDevID;
|
||||
SrxlTelemetryData payload;
|
||||
uint16_t crc;
|
||||
} PACKED SrxlTelemetryPacket;
|
||||
|
||||
// Signal Quality
|
||||
typedef struct SrxlRssiPacket
|
||||
{
|
||||
SrxlHeader hdr;
|
||||
uint8_t request;
|
||||
int8_t antennaA;
|
||||
int8_t antennaB;
|
||||
int8_t antennaC;
|
||||
int8_t antennaD;
|
||||
uint16_t crc;
|
||||
} PACKED SrxlRssiPacket;
|
||||
|
||||
// Parameter Config
|
||||
typedef struct SrxlParamPacket
|
||||
{
|
||||
SrxlHeader hdr;
|
||||
uint8_t request;
|
||||
uint8_t destDevID;
|
||||
uint32_t paramID;
|
||||
uint32_t paramVal;
|
||||
uint16_t crc;
|
||||
} PACKED SrxlParamPacket;
|
||||
|
||||
// VTX Data
|
||||
typedef struct SrxlVtxData
|
||||
{
|
||||
uint8_t band; // VTX Band (0 = Fatshark, 1 = Raceband, 2 = E, 3 = B, 4 = A)
|
||||
uint8_t channel; // VTX Channel (0-7)
|
||||
uint8_t pit; // Pit/Race mode (0 = Race, 1 = Pit). Race = normal power, Pit = reduced power
|
||||
uint8_t power; // VTX Power (0 = Off, 1 = 1mw to 14mW, 2 = 15mW to 25mW, 3 = 26mW to 99mW,
|
||||
// 4 = 100mW to 299mW, 5 = 300mW to 600mW, 6 = 601mW+, 7 = manual control)
|
||||
uint16_t powerDec; // VTX Power as a decimal 1mw/unit
|
||||
uint8_t region; // Region (0 = USA, 1 = EU)
|
||||
} PACKED SrxlVtxData;
|
||||
|
||||
// Forward Programming Data
|
||||
typedef struct SrxlFwdPgmData
|
||||
{
|
||||
uint8_t rfu[3]; // 0 for now -- used to word-align data
|
||||
uint8_t data[FWD_PGM_MAX_DATA_SIZE];
|
||||
} PACKED SrxlFwdPgmData;
|
||||
|
||||
// Channel Data
|
||||
typedef struct SrxlChannelData
|
||||
{
|
||||
int8_t rssi; // Best RSSI when sending channel data, or dropout RSSI when sending failsafe data
|
||||
uint16_t frameLosses; // Total lost frames (or fade count when sent from Remote Rx to main Receiver)
|
||||
uint32_t mask; // Set bits indicate that channel data with the corresponding index is present
|
||||
uint16_t values[32]; // Channel values, shifted to full 16-bit range (32768 = mid-scale); lowest 2 bits RFU
|
||||
} PACKED SrxlChannelData;
|
||||
|
||||
// Control Data
|
||||
typedef struct SrxlControlData
|
||||
{
|
||||
uint8_t cmd;
|
||||
uint8_t replyID;
|
||||
union
|
||||
{
|
||||
SrxlChannelData channelData; // Used for Channel Data and Failsafe Channel Data commands
|
||||
SrxlVtxData vtxData; // Used for VTX commands
|
||||
SrxlFwdPgmData fpData; // Used to pass forward programming data to an SRXL device
|
||||
};
|
||||
} PACKED SrxlControlData;
|
||||
|
||||
typedef struct SrxlControlPacket
|
||||
{
|
||||
SrxlHeader hdr;
|
||||
SrxlControlData payload;
|
||||
// uint16_t crc; // NOTE: Since this packet is variable-length, we can't use this value anyway
|
||||
} PACKED SrxlControlPacket;
|
||||
|
||||
// SRXL Packets
|
||||
typedef union
|
||||
{
|
||||
SrxlHeader header;
|
||||
SrxlBindPacket bind;
|
||||
SrxlHandshakePacket handshake;
|
||||
SrxlTelemetryPacket telemetry;
|
||||
SrxlRssiPacket rssi;
|
||||
SrxlParamPacket parameter;
|
||||
SrxlControlPacket control;
|
||||
uint8_t raw[SRXL_MAX_BUFFER_SIZE];
|
||||
} SrxlPacket;
|
||||
|
||||
// SRXL full device identifier -- SRXL Device ID with bus number
|
||||
typedef union
|
||||
{
|
||||
struct
|
||||
{
|
||||
uint8_t deviceID;
|
||||
uint8_t busIndex;
|
||||
};
|
||||
uint16_t word;
|
||||
} PACKED SrxlFullID;
|
||||
|
||||
// Restore packing back to default
|
||||
#undef PACKED
|
||||
#ifndef __GNUC__
|
||||
#pragma pack(pop)
|
||||
#endif
|
||||
|
||||
// Global vars
|
||||
extern SrxlChannelData srxlChData;
|
||||
extern SrxlTelemetryData srxlTelemData;
|
||||
extern SrxlVtxData srxlVtxData;
|
||||
|
||||
// Include config here, after all typedefs that might be needed within it
|
||||
#include "spm_srxl_config.h"
|
||||
|
||||
#if !defined(SRXL_NUM_OF_BUSES)
|
||||
#error "SRXL_NUM_OF_BUSES must be defined in spm_srxl_config.h!"
|
||||
#elif SRXL_NUM_OF_BUSES <= 0
|
||||
#error "SRXL_NUM_OF_BUSES must be defined in spm_srxl_config.h!"
|
||||
#elif SRXL_NUM_OF_BUSES > 1
|
||||
#define SRXL_IS_HUB
|
||||
#endif
|
||||
#define SRXL_ALL_BUSES ((1u << SRXL_NUM_OF_BUSES) - 1)
|
||||
#define SRXL_MAX_RCVRS (2 * SRXL_NUM_OF_BUSES)
|
||||
#ifndef SRXL_CRC_OPTIMIZE_MODE // NOTE: This should be set in spm_srxl_config.h
|
||||
#define SRXL_CRC_OPTIMIZE_MODE SRXL_CRC_OPTIMIZE_SPEED
|
||||
#endif
|
||||
|
||||
#define RSSI_RCVD_NONE (0)
|
||||
#define RSSI_RCVD_DBM (1)
|
||||
#define RSSI_RCVD_PCT (2)
|
||||
#define RSSI_RCVD_BOTH (3)
|
||||
|
||||
// Internal types
|
||||
typedef enum
|
||||
{
|
||||
SrxlState_Disabled, // Default state before initialized or if bus is subsequently disabled
|
||||
SrxlState_ListenOnStartup, // Wait 50ms to see if anything is already talking (i.e. we probably browned out)
|
||||
SrxlState_SendHandshake, // Call when handshake should be sent every 50ms
|
||||
SrxlState_ListenForHandshake, // Wait at least 150ms more for handshake request
|
||||
SrxlState_Running, // Normal run state
|
||||
SrxlState_SendTelemetry, // Send telemetry reply when requested
|
||||
SrxlState_SendVTX, // Send VTX packet when needed
|
||||
SrxlState_SendEnterBind,
|
||||
SrxlState_SendBoundDataReport,
|
||||
SrxlState_SendSetBindInfo,
|
||||
} SrxlState;
|
||||
|
||||
//#ifdef SRXL_IS_HUB
|
||||
typedef struct SrxlRcvrEntry
|
||||
{
|
||||
uint8_t deviceID; // SRXL device ID of the receiver
|
||||
uint8_t busBits; // Supports 8 buses, with each bit corresponding to busIndex (bit 0 = bus 0, bit 7 = bus 7)
|
||||
uint8_t info; // Info bits reported during handshake - See SRXL_DEVINFO_XXX mask bits in header
|
||||
uint8_t rssiRcvd; // 0 = none, 1 = dBm, 2 = percent, 3 = both dBm and percent
|
||||
int8_t rssi_dBm; // Latest RSSI dBm value reported by receiver (negative, varies with receiver type)
|
||||
int8_t rssi_Pct; // Latest RSSI percent range estimate reported by receiver (0-100)
|
||||
uint16_t fades; // Latest number of fades reported for a given receiver
|
||||
uint32_t channelMask; // Latest channel mask for channels provided in channel data packet (0 during fade)
|
||||
} SrxlRcvrEntry;
|
||||
|
||||
typedef struct SrxlReceiverInfo
|
||||
{
|
||||
SrxlRcvrEntry rcvr[SRXL_MAX_RCVRS]; // Stats for each receiver, filled when ch data is received
|
||||
SrxlRcvrEntry* rcvrSorted[SRXL_MAX_RCVRS]; // Pointers to receiver entries sorted in telemetry range order
|
||||
uint8_t rcvrSortInsert; // Index into rcvrSorted where full-range telem rcvrs should be inserted
|
||||
uint8_t rcvrCount; // Number of entries in rcvr[] and rcvrSorted[]
|
||||
uint8_t rxBusBits;
|
||||
int8_t bestRssi_dBm;
|
||||
int8_t bestRssi_Pct;
|
||||
uint8_t lossCountdown; // Reset to lossHoldCount when frame is good, and decrement for each consecutive
|
||||
// frame loss -- when we get to 0, convert lossHoldCount frame losses to a hold
|
||||
uint8_t lossHoldCount; // Consecutive frame losses required to count as hold
|
||||
uint16_t frameLosses; // Increment each time all receivers are in frame loss -- if 45
|
||||
// consecutive, subtract those and increment holds
|
||||
uint16_t holds; // Increment each time 45 or more consecutive frames are lost (but don't keep
|
||||
// incrementing once in that state)
|
||||
SrxlRcvrEntry* pTelemRcvr; // Pointer to current assigned telemetry receiver (used for checking
|
||||
// for fade to know when to switch)
|
||||
SrxlRcvrEntry* pBindRcvr; // Pointer to receiver that we told to Enter Bind Mode (used to
|
||||
// process Bound Data Report and send Set Bind Info)
|
||||
} SrxlReceiverStats;
|
||||
//#endif
|
||||
|
||||
typedef struct SrxlDevEntry
|
||||
{
|
||||
uint8_t deviceID;
|
||||
uint8_t priority; // Requested telemetry priority of this device
|
||||
uint8_t info; // Refer to SRXL_DEVINFO_XXX mask bits in header
|
||||
uint8_t rfu;
|
||||
} SrxlDevEntry;
|
||||
|
||||
typedef struct SrxlTxFlags
|
||||
{
|
||||
unsigned int enterBind : 1;
|
||||
unsigned int getBindInfo : 1;
|
||||
unsigned int setBindInfo : 1;
|
||||
unsigned int broadcastBindInfo : 1;
|
||||
unsigned int reportBindInfo : 1;
|
||||
unsigned int sendVtxData : 1;
|
||||
unsigned int sendFwdPgmData : 1;
|
||||
} SrxlTxFlags;
|
||||
|
||||
typedef struct SrxlBus
|
||||
{
|
||||
SrxlPacket srxlOut; // Transmit packet buffer
|
||||
SrxlPacket srxlIn; // Receive packet buffer
|
||||
|
||||
SrxlState state; // Current state of SRXL state machine
|
||||
SrxlFullID fullID; // Device ID and Bus Index of this device, set during init
|
||||
uint8_t rxDevCount; // Number of other SRXL devices discovered via handshake
|
||||
SrxlDevEntry rxDev[SRXL_MAX_DEVICES]; // Device entries for tracking SRXL telemetry priorities
|
||||
#ifdef SRXL_INCLUDE_MASTER_CODE
|
||||
uint16_t rxDevAge[SRXL_MAX_DEVICES]; // Telemetry age value for the associated device
|
||||
#endif
|
||||
uint16_t rxDevPrioritySum; // Sum of priorities requested for each discovered SRXL device
|
||||
uint16_t timeoutCount_ms; // Milliseconds since SRXL packet was received (incremented in srxlRun)
|
||||
uint8_t requestID; // Device ID to poll
|
||||
uint8_t baudSupported; // Baud rates this device can do: 0 = 115200, 1 = 400000
|
||||
uint8_t baudRate; // Current baud rate: 0 = 115200, 1 = 400000
|
||||
uint8_t frameErrCount; // Number of consecutive missed frames
|
||||
SrxlTxFlags txFlags; // Pending outgoing packet types
|
||||
void* uart; // Index number of UART tied to this SRXL bus
|
||||
SrxlRcvrEntry* pMasterRcvr; // Receiver entry for the bus master, if one exists
|
||||
bool master; // True if this device is the bus master on this bus
|
||||
bool initialized; // True when this SRXL bus is initialized
|
||||
} SrxlBus;
|
||||
|
||||
typedef struct SrxlDevice
|
||||
{
|
||||
SrxlDevEntry devEntry; // Device info for this local device, shared across all buses.
|
||||
uint32_t uid; // ID statistically likely to be unique (Random, hash of serial, etc.)
|
||||
SrxlRcvrEntry* pRcvr; // Pointer to our receiver entry, if we're a receiver (don't set for
|
||||
// flight controller acting as hub -- only true receiver)
|
||||
bool vtxProxy; // Set true if this device can and should respond to VTX commands
|
||||
} SrxlDevice;
|
||||
|
||||
|
||||
// Function prototypes
|
||||
bool srxlInitDevice(uint8_t deviceID, uint8_t priority, uint8_t info, uint32_t uid);
|
||||
bool srxlInitBus(uint8_t busIndex, void* uart, uint8_t baudSupported);
|
||||
bool srxlIsBusMaster(uint8_t busIndex);
|
||||
uint16_t srxlGetTimeoutCount_ms(uint8_t busIndex);
|
||||
uint8_t srxlGetDeviceID(uint8_t busIndex);
|
||||
bool srxlParsePacket(uint8_t busIndex, uint8_t *packet, uint8_t length);
|
||||
void srxlRun(uint8_t busIndex, int16_t timeoutDelta_ms);
|
||||
bool srxlEnterBind(uint8_t bindType, bool broadcast);
|
||||
bool srxlSetBindInfo(uint8_t bindType, uint64_t guid, uint32_t uid);
|
||||
void srxlOnFrameError(uint8_t busIndex);
|
||||
SrxlFullID srxlGetTelemetryEndpoint(void);
|
||||
bool srxlSetVtxData(SrxlVtxData *pVtxData);
|
||||
bool srxlPassThruFwdPgm(uint8_t *pData, uint8_t length);
|
||||
void srxlSetHoldThreshold(uint8_t countdownReset);
|
||||
void srxlClearCommStats(void);
|
||||
bool srxlUpdateCommStats(bool isFade);
|
||||
|
||||
#ifdef __cplusplus
|
||||
} // extern "C"
|
||||
#endif
|
||||
|
||||
#endif //__SRXL_H__
|
|
@ -0,0 +1,144 @@
|
|||
/*
|
||||
MIT License
|
||||
|
||||
Copyright (c) 2019 Horizon Hobby, LLC
|
||||
|
||||
Permission is hereby granted, free of charge, to any person obtaining a copy
|
||||
of this software and associated documentation files (the "Software"), to deal
|
||||
in the Software without restriction, including without limitation the rights
|
||||
to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
|
||||
copies of the Software, and to permit persons to whom the Software is
|
||||
furnished to do so, subject to the following conditions:
|
||||
|
||||
The above copyright notice and this permission notice shall be included in all
|
||||
copies or substantial portions of the Software.
|
||||
|
||||
THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
|
||||
IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
|
||||
FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
|
||||
AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
|
||||
LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
|
||||
OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
|
||||
SOFTWARE.
|
||||
*/
|
||||
|
||||
// This file is automatically included within spm_srxl.h -- do not include elsewhere!
|
||||
|
||||
#ifndef _SRXL_CONFIG_H_
|
||||
#define _SRXL_CONFIG_H_
|
||||
|
||||
//### USER PROVIDED HEADER FUNCTIONS AND FORWARD DECLARATIONS ###
|
||||
|
||||
// User included headers/declarations to access interface functions required below
|
||||
//#include <AP_HAL/AP_HAL.h>
|
||||
|
||||
//void userProvidedFillSrxlTelemetry(SrxlTelemetryData* pTelemetry);
|
||||
//void userProvidedReceivedChannelData(SrxlChannelData* pChannelData);
|
||||
//void userProvidedHandleVtxData(SrxlVtxData* pVtxData);
|
||||
|
||||
//### USER CONFIGURATION ###
|
||||
|
||||
// Set this value to the number of physically separate SRXL buses on the device
|
||||
#define SRXL_NUM_OF_BUSES 1
|
||||
|
||||
// Set this to the appropriate device ID (See Section 7.1.1 in Spektrum Bi-Directional SRXL Documentation).
|
||||
// Typical values are:
|
||||
// Flight Controller = 0x31 (or possibly 0x30 if connected to Base Receiver instead of Remote Receiver)
|
||||
// Smart ESC = 0x40
|
||||
// VTX = 0x81
|
||||
// NOTE: This value is not used internally -- it is passed as a parameter to srxlInit() in the example app
|
||||
#define SRXL_DEVICE_ID 0x31
|
||||
|
||||
// Set this to the desired priority level for sending telemetry, ranging from 0 to 100.
|
||||
// Generally, this number should be 10 times the number of different telemetry packets to regularly send.
|
||||
// If there are telemetry messages that should be sent more often, increase this value.
|
||||
// If there are messages that are rarely sent, add less than 10 for those.
|
||||
// For example, if you had two normal priority messages and one that you plan to send twice as often as those,
|
||||
// you could set the priority to 40 (10 + 10 + 2*10)
|
||||
// NOTE: This value is not used internally -- it is passed as a parameter to srxlInit() in the example app
|
||||
#define SRXL_DEVICE_PRIORITY 20
|
||||
|
||||
// Set these information bits based on the capabilities of the device.
|
||||
// The only bit currently applicable to third-party devices is the SRXL_DEVINFO_FWD_PROG_SUPPORT flag,
|
||||
// which should be set if you would like to allow Forward Programming of the device via SRXL pass-through.
|
||||
#define SRXL_DEVICE_INFO (SRXL_DEVINFO_NO_RF)
|
||||
|
||||
// Set this value to 0 for 115200 baud only, or 1 for 400000 baud support
|
||||
#define SRXL_SUPPORTED_BAUD_RATES 0
|
||||
|
||||
// Set this value to choose which code to include for CRC computation. Choices are:
|
||||
// SRXL_CRC_OPTIMIZE_SPEED -- Uses table lookup for CRC computation (requires 512 const bytes for CRC table)
|
||||
// SRXL_CRC_OPTIMIZE_SIZE -- Uses bitwise operations for smaller code size but slower execution
|
||||
// SRXL_CRC_OPTIMIZE_STM_HW -- Uses STM32 register-level hardware acceleration (only available on STM32F30x devices for now)
|
||||
// SRXL_CRC_OPTIMIZE_STM_HAL -- Uses STM32Cube HAL driver for hardware acceleration (only available on STM32F3/F7) -- see srxlCrc16() for details on HAL config
|
||||
|
||||
#define SRXL_CRC_EXTERNAL(packet, length, crc) crc16_ccitt(packet, length, crc)
|
||||
|
||||
extern uint16_t crc16_ccitt(const uint8_t *buf, uint32_t len, uint16_t crc);
|
||||
#define SRXL_CRC_OPTIMIZE_MODE SRXL_CRC_EXTERNAL
|
||||
|
||||
// If using STM32 hardware CRC acceleration above, set this flag to the target family. Choices are:
|
||||
// SRXL_STM_TARGET_F3
|
||||
// SRXL_STM_TARGET_F7
|
||||
#define SRXL_STM_TARGET_FAMILY SRXL_STM_TARGET_F3
|
||||
|
||||
// If using SRXL_CRC_OPTIMIZE_STM_HW and the CRC hardware is shared with non-SRXL code, then
|
||||
// uncomment the following flag to save and restore the CRC registers after use by SRXL:
|
||||
//#define SRXL_SAVE_HW_CRC_CONTEXT
|
||||
|
||||
// Uncomment the following flag if your code must support Forward Programming received via SRXL
|
||||
//#define SRXL_INCLUDE_FWD_PGM_CODE
|
||||
|
||||
//### USER PROVIDED INTERFACE FUNCTIONS ###
|
||||
|
||||
// User-provided routine to change the baud rate settings on the given UART:
|
||||
// uart - the same uint8_t value as the uart parameter passed to srxlInit()
|
||||
// baudRate - the actual baud rate (currently either 115200 or 400000)
|
||||
void srxlChangeBaudRate(void* uart, uint32_t baudRate);
|
||||
|
||||
// User-provided routine to actually transmit a packet on the given UART:
|
||||
// uart - the same uint8_t value as the uart parameter passed to srxlInit()
|
||||
// pBuffer - a pointer to an array of uint8_t values to send over the UART
|
||||
// length - the number of bytes contained in pBuffer that should be sent
|
||||
void srxlSendOnUart(void* uart, uint8_t* pBuffer, uint8_t length);
|
||||
|
||||
// User-provided callback routine to fill in the telemetry data to send to the master when requested:
|
||||
// pTelemetryData - a pointer to the 16-byte SrxlTelemetryData transmit buffer to populate
|
||||
// NOTE: srxlTelemData is available as a global variable, so the memcpy line commented out below
|
||||
// could be used if you would prefer to just populate that with the next outgoing telemetry packet.
|
||||
void srxlFillTelemetry(SrxlTelemetryData* pTelemetryData);
|
||||
|
||||
// User-provided callback routine that is called whenever a control data packet is received:
|
||||
// pChannelData - a pointer to the received SrxlChannelData structure for manual parsing
|
||||
// isFailsafe - true if channel data is set to failsafe values, else false.
|
||||
// NOTE: srxlChData is available as a global variable that contains all of the latest values
|
||||
// for channel data, so this callback is intended to be used if more control is desired.
|
||||
// It might make sense to only use this to trigger your own handling of the received servo values.
|
||||
void srxlReceivedChannelData(SrxlChannelData* pChannelData, bool isFailsafe);
|
||||
|
||||
// User-provided callback routine to handle reception of a bound data report (either requested or unprompted).
|
||||
// Return true if you want this bind information set automatically for all other receivers on all SRXL buses.
|
||||
bool srxlOnBind(SrxlFullID device, SrxlBindData info);
|
||||
|
||||
// User-provided callback routine to handle reception of a VTX control packet.
|
||||
void srxlOnVtx(SrxlVtxData* pVtxData);
|
||||
|
||||
// Optional user-provided callback routine to handle Forward Programming command locally if supported
|
||||
#ifdef SRXL_INCLUDE_FWD_PGM_CODE
|
||||
static inline void srxlOnFwdPgm(uint8_t* pData, uint8_t dataLength)
|
||||
{
|
||||
// TODO: Pass data to Forward Programming library
|
||||
}
|
||||
#endif // SRXL_INCLUDE_FWD_PGM_CODE
|
||||
|
||||
// User-provided routine to enter a critical section (only needed with multiple buses or if HW CRC is used externally)
|
||||
static inline void srxlEnterCriticalSection(void)
|
||||
{
|
||||
}
|
||||
|
||||
// User-provided routine to exit a critical section (only needed with multiple buses or if HW CRC is used externally)
|
||||
static inline void srxlExitCriticalSection(void)
|
||||
{
|
||||
}
|
||||
|
||||
#endif // _SRXL_CONFIG_H_
|
Loading…
Reference in New Issue