diff --git a/libraries/AP_RCProtocol/AP_RCProtocol.cpp b/libraries/AP_RCProtocol/AP_RCProtocol.cpp index 86756fc6b1..9ce0d141b5 100644 --- a/libraries/AP_RCProtocol/AP_RCProtocol.cpp +++ b/libraries/AP_RCProtocol/AP_RCProtocol.cpp @@ -15,6 +15,7 @@ * Code by Andrew Tridgell and Siddharth Bharat Purohit */ +#include #include "AP_RCProtocol.h" #include "AP_RCProtocol_PPMSum.h" #include "AP_RCProtocol_DSM.h" @@ -22,7 +23,9 @@ #include "AP_RCProtocol_SBUS.h" #include "AP_RCProtocol_SUMD.h" #include "AP_RCProtocol_SRXL.h" +#if !APM_BUILD_TYPE(APM_BUILD_iofirmware) #include "AP_RCProtocol_SRXL2.h" +#endif #include "AP_RCProtocol_ST24.h" #include "AP_RCProtocol_FPort.h" #include @@ -38,7 +41,9 @@ 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); +#if !APM_BUILD_TYPE(APM_BUILD_iofirmware) backend[AP_RCProtocol::SRXL2] = new AP_RCProtocol_SRXL2(*this); +#endif backend[AP_RCProtocol::ST24] = new AP_RCProtocol_ST24(*this); backend[AP_RCProtocol::FPORT] = new AP_RCProtocol_FPort(*this, true); } diff --git a/libraries/AP_RCProtocol/AP_RCProtocol_SRXL2.cpp b/libraries/AP_RCProtocol/AP_RCProtocol_SRXL2.cpp index 57f3bdd770..d38fd3da5c 100644 --- a/libraries/AP_RCProtocol/AP_RCProtocol_SRXL2.cpp +++ b/libraries/AP_RCProtocol/AP_RCProtocol_SRXL2.cpp @@ -17,15 +17,15 @@ Code by Andy Piper */ -#include "spm_srxl.h" - #include "AP_RCProtocol.h" #include "AP_RCProtocol_SRXL.h" #include "AP_RCProtocol_SRXL2.h" #include -#include +#include #include +#include "spm_srxl.h" + extern const AP_HAL::HAL& hal; //#define SRXL2_DEBUG #ifdef SRXL2_DEBUG @@ -51,34 +51,26 @@ AP_RCProtocol_SRXL2::AP_RCProtocol_SRXL2(AP_RCProtocol &_frontend) : AP_RCProtoc } // 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)) { + if (!srxlInitBus(0, 0, 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; } + _frame_len_full = 0U; + _buflen = 0; + _decode_state_next = STATE_IDLE; } switch (_decode_state) { @@ -100,6 +92,12 @@ void AP_RCProtocol_SRXL2::_process_byte(uint32_t timestamp_us, uint8_t byte) // parse the length if (_buflen == SRXL2_HEADER_LEN) { _frame_len_full = _buffer[2]; + // check for garbage frame + if (_frame_len_full > SRXL2_FRAMELEN_MAX) { + _decode_state = STATE_IDLE; + _buflen = 0; + _frame_len_full = 0; + } return; } @@ -113,12 +111,15 @@ void AP_RCProtocol_SRXL2::_process_byte(uint32_t timestamp_us, uint8_t byte) 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; + _buflen = 0; } else { _decode_state_next = STATE_COLLECT; } @@ -129,17 +130,19 @@ void AP_RCProtocol_SRXL2::_process_byte(uint32_t timestamp_us, uint8_t byte) } _decode_state = _decode_state_next; - _last_data_us = timestamp_us; } void AP_RCProtocol_SRXL2::update(void) { - // it's not clear this is actually required, perhaps on power loss? - if (frontend.protocol_detected() == AP_RCProtocol::SRXL2) { + // on a SPM4650 with telemetry the frame rate is 91Hz equating to around 10ms per frame + // however only half of them can return telemetry, so the maximum telemetry rate is 46Hz + // also update() is run immediately after check_added_uart() and so in general the delay is < 5ms + // to be safe we will only run if the timeout exceeds 50ms + if (_last_run_ms > 0) { 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) { + if (delay > 50) { srxlRun(0, delay); _last_run_ms = now; } @@ -209,15 +212,15 @@ void AP_RCProtocol_SRXL2::send_on_uart(uint8_t* pBuffer, uint8_t 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 + if (have_UART()) { + // 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. incoming packets at max 800bits @91Hz @115k baud gives total budget of 11ms + // per packet of which we need 7ms to receive a packet. outgoing packets are 220 bits which require 2ms to send + // leaving at most 2ms of delay that can be tolerated uint64_t tend = get_UART()->receive_time_constraint_us(1); uint64_t now = AP_HAL::micros64(); uint64_t tdelay = now - tend; - if (tdelay > 2500) { + if (tdelay > 2000) { // we've been too slow in responding return; } @@ -243,11 +246,11 @@ void AP_RCProtocol_SRXL2::change_baud_rate(uint32_t 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); + get_UART()->set_flow_control(AP_HAL::UARTDriver::FLOW_CONTROL_DISABLE); + get_UART()->set_unbuffered_writes(true); } -#endif } // SRXL2 library callbacks below @@ -255,7 +258,7 @@ void AP_RCProtocol_SRXL2::_change_baud_rate(uint32_t baudrate) // 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) +void srxlChangeBaudRate(uint8_t uart, uint32_t baudRate) { AP_RCProtocol_SRXL2::change_baud_rate(baudRate); @@ -265,7 +268,7 @@ void srxlChangeBaudRate(void* this_ptr, uint32_t baudRate) // 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) +void srxlSendOnUart(uint8_t uart, uint8_t* pBuffer, uint8_t length) { AP_RCProtocol_SRXL2::send_on_uart(pBuffer, length); } @@ -276,7 +279,7 @@ void srxlSendOnUart(void* this_ptr, uint8_t* pBuffer, uint8_t length) // 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) +#if HAL_SPEKTRUM_TELEM_ENABLED && !APM_BUILD_TYPE(APM_BUILD_iofirmware) AP_Spektrum_Telem::get_telem_data(pTelemetryData->raw); #endif } diff --git a/libraries/AP_RCProtocol/AP_RCProtocol_SRXL2.h b/libraries/AP_RCProtocol/AP_RCProtocol_SRXL2.h index 518864ae5c..217f4521bd 100644 --- a/libraries/AP_RCProtocol/AP_RCProtocol_SRXL2.h +++ b/libraries/AP_RCProtocol/AP_RCProtocol_SRXL2.h @@ -26,7 +26,6 @@ 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; @@ -53,7 +52,6 @@ private: 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 */ @@ -67,6 +65,4 @@ private: 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}; }; diff --git a/libraries/AP_RCProtocol/examples/RCProtocolDecoder/RCProtocolDecoder.cpp b/libraries/AP_RCProtocol/examples/RCProtocolDecoder/RCProtocolDecoder.cpp index 716db87434..04836e01d8 100644 --- a/libraries/AP_RCProtocol/examples/RCProtocolDecoder/RCProtocolDecoder.cpp +++ b/libraries/AP_RCProtocol/examples/RCProtocolDecoder/RCProtocolDecoder.cpp @@ -13,7 +13,16 @@ * with this program. If not, see . */ /* - decode RC input using SITL on command line + * decode RC input using SITL on command line + * + * To use this as an RC protocol decoder for SITL with a real transmitter: + * + * 1. Compile using Linux - SITL has timing that is too variable + * 2. Connect an RX device to an FTDI adapter + * 3. Set the FTDI serial port to 115k baud, 8N1 + * 4. Set the FTDI serial BM options to 1ms latency (very important) + * 5. Set the tty using: stty -F raw 115200 + * 6. Run this sketch providing the serial device name as an argument. RC values will be automatically written to the SITL RC port */ #include @@ -25,8 +34,10 @@ void loop(); #if CONFIG_HAL_BOARD == HAL_BOARD_LINUX || CONFIG_HAL_BOARD == HAL_BOARD_SITL +#include #include #include +#include #include #include #include @@ -62,12 +73,15 @@ private: #include RC_Channels_RC _rc; +SocketAPM rc_socket{true}; // 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; static int fd; +static uint16_t chan[16]; +static uint8_t nchan = 0; // setup routine void setup() @@ -106,30 +120,42 @@ void setup() } tcflush(fd, TCIOFLUSH); - rcprot = new AP_RCProtocol(); + rcprot = &AP::RC(); +#if CONFIG_HAL_BOARD != HAL_BOARD_SITL rcprot->init(); +#endif + // proxy to SITL's rcin port + rc_socket.connect("0.0.0.0", 5501); } //Main loop where the action takes place void loop() { - uint8_t buf[32]; + uint8_t buf[62]; // lowest USB buffer size is 62 user bytes + ssize_t ret = read(fd, buf, sizeof(buf)); - if (ret <= 0) { - return; - } + for (uint8_t i=0; iprocess_byte(buf[i], 115200); if (rcprot->new_input()) { - uint8_t nchan = rcprot->num_channels(); + nchan = MIN(rcprot->num_channels(), 16); + rcprot->read(chan, nchan); printf("%u: ", nchan); for (uint8_t j=0; jread(j); - printf("%04u ", v); + // normalize data for SITL + chan[j] = constrain_int16(chan[j], 1100, 1900); + printf("%04u ", chan[j]); } printf("\n"); + } } + // SITL expects either 8 or 16 channels, send whether we got data or not + if (nchan <= 8) { + rc_socket.send(chan, 8 * 2); + } else { + rc_socket.send(chan, 16 * 2); + } } #else @@ -139,4 +165,16 @@ void loop() {} #endif // CONFIG_HAL_BOARD -AP_HAL_MAIN(); +AP_HAL::HAL::FunCallbacks callbacks(setup, loop); +extern "C" { +int main(int argc, char* const argv[]); +int main(int argc, char* const argv[]) { +#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX + if (argc > 1) { + devicename = argv[1]; + } +#endif + hal.run(argc, argv, &callbacks); + return 0; +} +} diff --git a/libraries/AP_RCProtocol/spm_srxl.c b/libraries/AP_RCProtocol/spm_srxl.cpp similarity index 97% rename from libraries/AP_RCProtocol/spm_srxl.c rename to libraries/AP_RCProtocol/spm_srxl.cpp index d418dd5f82..8dfcf495b5 100644 --- a/libraries/AP_RCProtocol/spm_srxl.c +++ b/libraries/AP_RCProtocol/spm_srxl.cpp @@ -80,19 +80,21 @@ SrxlVtxData srxlVtxData = {0, 0, 1, 0, 0, 1}; /// LOCAL VARIABLES /// -SrxlDevice srxlThisDev = {0}; -SrxlBus srxlBus[SRXL_NUM_OF_BUSES]; -bool srxlChDataIsFailsafe = false; -bool srxlTelemetryPhase = false; -uint32_t srxlFailsafeChMask = 0; // Tracks all active channels for use during failsafe transmission -SrxlBindData srxlBindInfo = {0, 0, 0, 0}; -SrxlReceiverStats srxlRx = {0}; -uint16_t srxlTelemSuppressCount = 0; +static SrxlDevice srxlThisDev = {0}; +static SrxlBus srxlBus[SRXL_NUM_OF_BUSES]; +static bool srxlChDataIsFailsafe = false; +static bool srxlTelemetryPhase = false; +#ifdef SRXL_INCLUDE_MASTER_CODE +static uint32_t srxlFailsafeChMask = 0; // Tracks all active channels for use during failsafe transmission +#endif +static SrxlBindData srxlBindInfo = {0, 0, 0, 0}; +static SrxlReceiverStats srxlRx = {0}; +static uint16_t srxlTelemSuppressCount = 0; #ifdef SRXL_INCLUDE_FWD_PGM_CODE -SrxlFullID srxlFwdPgmDevice = {0, 0}; // Device that should accept Forward Programming connection by default -uint8_t srxlFwdPgmBuffer[FWD_PGM_MAX_DATA_SIZE] = {0}; -uint8_t srxlFwdPgmBufferLength = 0; +static SrxlFullID srxlFwdPgmDevice = {0, 0}; // Device that should accept Forward Programming connection by default +static uint8_t srxlFwdPgmBuffer[FWD_PGM_MAX_DATA_SIZE] = {0}; +static uint8_t srxlFwdPgmBufferLength = 0; #endif // Include additional header and externs if using STM32 hardware acceleration @@ -185,8 +187,8 @@ static uint16_t srxlCrc16(uint8_t* packet) // Output Data Inversion Mode = Disable // Input Data Format = Bytes crc = (uint16_t)HAL_CRC_Calculate(&hcrc, (uint32_t*)packet, length); -#elif(SRXL_CRC_OPTIMIZE_MODE == SRXL_CRC_EXTERNAL) - crc = SRXL_CRC_EXTERNAL(packet, length, crc); +#elif(SRXL_CRC_OPTIMIZE_MODE == SRXL_CRC_OPTIMIZE_EXTERNAL) + crc = SRXL_CRC_CALCULATE(packet, length, crc); #else // Default to table-lookup method uint8_t i; @@ -302,7 +304,7 @@ static inline SrxlRcvrEntry* srxlChooseTelemRcvr(void) } // Return pointer to device entry matching the given ID, or NULL if not found -SrxlDevEntry* srxlGetDeviceEntry(SrxlBus* pBus, uint8_t deviceID) +static SrxlDevEntry* srxlGetDeviceEntry(SrxlBus* pBus, uint8_t deviceID) { if(pBus) { @@ -317,7 +319,7 @@ SrxlDevEntry* srxlGetDeviceEntry(SrxlBus* pBus, uint8_t deviceID) } // Add an entry to our list of devices found on the SRXL bus (or update an entry if it already exists) -SrxlDevEntry* srxlAddDeviceEntry(SrxlBus* pBus, SrxlDevEntry devEntry) +static SrxlDevEntry* srxlAddDeviceEntry(SrxlBus* pBus, SrxlDevEntry devEntry) { // Don't allow broadcast or unknown device types to be added if(!pBus || devEntry.deviceID < 0x10 || devEntry.deviceID > 0xEF) @@ -421,7 +423,7 @@ bool srxlInitDevice(uint8_t deviceID, uint8_t priority, uint8_t info, uint32_t u @param baudSupported: 0 = 115200 baud, 1 = 400000 baud @return bool: True if SRXL bus was successfully initialized */ -bool srxlInitBus(uint8_t busIndex, void* uart, uint8_t baudSupported) +bool srxlInitBus(uint8_t busIndex, uint8_t uart, uint8_t baudSupported) { if(busIndex >= SRXL_NUM_OF_BUSES || !srxlThisDev.devEntry.deviceID) return false; @@ -485,7 +487,7 @@ uint8_t srxlGetDeviceID(uint8_t busIndex) @param srxlCmd: Specific type of packet to send @param replyID: Device ID of the device this Send command is targeting */ -void srxlSend(SrxlBus* pBus, SRXL_CMD srxlCmd, uint8_t replyID) +static void srxlSend(SrxlBus* pBus, SRXL_CMD srxlCmd, uint8_t replyID) { if(!pBus || !pBus->initialized) return; @@ -907,7 +909,9 @@ bool srxlParsePacket(uint8_t busIndex, uint8_t* packet, uint8_t length) if(pBindInfo->request == SRXL_BIND_REQ_BOUND_DATA) { // Call the user-defined callback -- if returns true, bind all other receivers - SrxlFullID boundID = {.deviceID = pBindInfo->deviceID, .busIndex = busIndex}; + SrxlFullID boundID; + boundID.deviceID = pBindInfo->deviceID; + boundID.busIndex = busIndex; if(srxlOnBind(boundID, pBindInfo->data)) { // Update the bind info @@ -1277,6 +1281,7 @@ void srxlOnFrameError(uint8_t busIndex) pBus->baudRate = SRXL_BAUD_400000; break; } + FALLTHROUGH; // else fall thru... } case SRXL_BAUD_400000: diff --git a/libraries/AP_RCProtocol/spm_srxl.h b/libraries/AP_RCProtocol/spm_srxl.h index a7f28dbc76..c1aecc3abd 100644 --- a/libraries/AP_RCProtocol/spm_srxl.h +++ b/libraries/AP_RCProtocol/spm_srxl.h @@ -77,6 +77,7 @@ static const uint8_t SRXL_DEFAULT_ID_OF_TYPE[16] = }; // Set SRXL_CRC_OPTIMIZE_MODE in spm_srxl_config.h to one of the following values +#define SRXL_CRC_OPTIMIZE_EXTERNAL (0) // Uses an external function defined by SRXL_CRC_EXTERNAL_FN for CRC #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) @@ -200,9 +201,8 @@ typedef enum // 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 SRXL_EXTERNAL_PACKED +#elif defined(__GNUC__) #define PACKED __attribute__((packed)) #else #pragma pack(push, 1) @@ -372,10 +372,12 @@ typedef union } PACKED SrxlFullID; // Restore packing back to default +#ifndef SRXL_EXTERNAL_PACKED #undef PACKED #ifndef __GNUC__ #pragma pack(pop) #endif +#endif // Global vars extern SrxlChannelData srxlChData; @@ -385,6 +387,10 @@ extern SrxlVtxData srxlVtxData; // Include config here, after all typedefs that might be needed within it #include "spm_srxl_config.h" +#ifndef FALLTHROUGH +#define FALLTHROUGH +#endif + #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 @@ -492,7 +498,7 @@ typedef struct SrxlBus 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 + uint8_t 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 @@ -510,7 +516,7 @@ typedef struct 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 srxlInitBus(uint8_t busIndex, uint8_t uart, uint8_t baudSupported); bool srxlIsBusMaster(uint8_t busIndex); uint16_t srxlGetTimeoutCount_ms(uint8_t busIndex); uint8_t srxlGetDeviceID(uint8_t busIndex); @@ -530,4 +536,10 @@ bool srxlUpdateCommStats(bool isFade); } // extern "C" #endif +#ifdef SRXL_INCLUDE_MASTER_CODE +// NOTE: Most user applications should not be an SRXL2 bus master, so master-specific code is not open. +// If your application requires this functionality, please inquire about this from Spektrum RC. +#include "spm_srxl_master.h" +#endif + #endif //__SRXL_H__ diff --git a/libraries/AP_RCProtocol/spm_srxl_config.h b/libraries/AP_RCProtocol/spm_srxl_config.h index 44fd054d29..9181182680 100644 --- a/libraries/AP_RCProtocol/spm_srxl_config.h +++ b/libraries/AP_RCProtocol/spm_srxl_config.h @@ -32,9 +32,11 @@ SOFTWARE. // User included headers/declarations to access interface functions required below //#include -//void userProvidedFillSrxlTelemetry(SrxlTelemetryData* pTelemetry); -//void userProvidedReceivedChannelData(SrxlChannelData* pChannelData); -//void userProvidedHandleVtxData(SrxlVtxData* pVtxData); +extern "C++" { +#include +#include +#include +} //### USER CONFIGURATION ### @@ -72,10 +74,9 @@ SOFTWARE. // 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) +#define SRXL_CRC_CALCULATE(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 +#define SRXL_CRC_OPTIMIZE_MODE SRXL_CRC_OPTIMIZE_EXTERNAL // If using STM32 hardware CRC acceleration above, set this flag to the target family. Choices are: // SRXL_STM_TARGET_F3 @@ -94,13 +95,13 @@ extern uint16_t crc16_ccitt(const uint8_t *buf, uint32_t len, uint16_t crc); // 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); +void srxlChangeBaudRate(uint8_t 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); +void srxlSendOnUart(uint8_t 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