mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-16 12:55:19 +03:00
Merge pull request #5990 from jflyper/bfdev-create-pg-rxSpiConfig
Add basic SPI RX configurability
This commit is contained in:
commit
418fd4beaa
32 changed files with 192 additions and 78 deletions
|
@ -32,6 +32,7 @@
|
|||
#include "build/build_config.h"
|
||||
|
||||
#include "pg/rx.h"
|
||||
#include "pg/rx_spi.h"
|
||||
|
||||
#include "drivers/io.h"
|
||||
#include "drivers/rx/rx_spi.h"
|
||||
|
|
|
@ -37,39 +37,39 @@
|
|||
#include "drivers/rcc.h"
|
||||
#include "drivers/system.h"
|
||||
|
||||
#include "pg/rx_spi.h"
|
||||
|
||||
#include "rx_spi.h"
|
||||
|
||||
#define DISABLE_RX() {IOHi(DEFIO_IO(RX_NSS_PIN));}
|
||||
#define ENABLE_RX() {IOLo(DEFIO_IO(RX_NSS_PIN));}
|
||||
static busDevice_t rxSpiDevice;
|
||||
static busDevice_t *busdev = &rxSpiDevice;
|
||||
|
||||
void rxSpiDeviceInit(void)
|
||||
#define DISABLE_RX() {IOHi(busdev->busdev_u.spi.csnPin);}
|
||||
#define ENABLE_RX() {IOLo(busdev->busdev_u.spi.csnPin);}
|
||||
|
||||
bool rxSpiDeviceInit(const rxSpiConfig_t *rxSpiConfig)
|
||||
{
|
||||
static bool hardwareInitialised = false;
|
||||
|
||||
if (hardwareInitialised) {
|
||||
return;
|
||||
if (!rxSpiConfig->spibus) {
|
||||
return false;
|
||||
}
|
||||
|
||||
const SPIDevice rxSPIDevice = spiDeviceByInstance(RX_SPI_INSTANCE);
|
||||
const IO_t rxCsPin = DEFIO_IO(RX_NSS_PIN);
|
||||
IOInit(rxCsPin, OWNER_RX_SPI_CS, rxSPIDevice + 1);
|
||||
spiBusSetInstance(busdev, spiInstanceByDevice(SPI_CFG_TO_DEV(rxSpiConfig->spibus)));
|
||||
|
||||
const IO_t rxCsPin = IOGetByTag(rxSpiConfig->csnTag);
|
||||
IOInit(rxCsPin, OWNER_RX_SPI_CS, 0);
|
||||
IOConfigGPIO(rxCsPin, SPI_IO_CS_CFG);
|
||||
busdev->busdev_u.spi.csnPin = rxCsPin;
|
||||
|
||||
DISABLE_RX();
|
||||
|
||||
#ifdef RX_SPI_INSTANCE
|
||||
spiSetDivisor(RX_SPI_INSTANCE, SPI_CLOCK_STANDARD);
|
||||
#endif
|
||||
hardwareInitialised = true;
|
||||
spiSetDivisor(busdev->busdev_u.spi.instance, SPI_CLOCK_STANDARD);
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
uint8_t rxSpiTransferByte(uint8_t data)
|
||||
{
|
||||
#ifdef RX_SPI_INSTANCE
|
||||
return spiTransferByte(RX_SPI_INSTANCE, data);
|
||||
#else
|
||||
return 0;
|
||||
#endif
|
||||
return spiTransferByte(busdev->busdev_u.spi.instance, data);
|
||||
}
|
||||
|
||||
uint8_t rxSpiWriteByte(uint8_t data)
|
||||
|
|
|
@ -24,7 +24,9 @@
|
|||
|
||||
#define RX_SPI_MAX_PAYLOAD_SIZE 32
|
||||
|
||||
void rxSpiDeviceInit(void);
|
||||
struct rxSpiConfig_s;
|
||||
|
||||
bool rxSpiDeviceInit(const struct rxSpiConfig_s *rxSpiConfig);
|
||||
uint8_t rxSpiTransferByte(uint8_t data);
|
||||
uint8_t rxSpiWriteByte(uint8_t data);
|
||||
uint8_t rxSpiWriteCommand(uint8_t command, uint8_t data);
|
||||
|
|
|
@ -98,6 +98,7 @@
|
|||
#include "pg/piniobox.h"
|
||||
#include "pg/pg.h"
|
||||
#include "pg/rx.h"
|
||||
#include "pg/rx_spi.h"
|
||||
#include "pg/rx_pwm.h"
|
||||
#include "pg/sdcard.h"
|
||||
#include "pg/vcd.h"
|
||||
|
@ -465,7 +466,10 @@ void init(void)
|
|||
adcConfigMutable()->current.enabled = (batteryConfig()->currentMeterSource == CURRENT_METER_ADC);
|
||||
|
||||
// The FrSky D SPI RX sends RSSI_ADC_PIN (if configured) as A2
|
||||
adcConfigMutable()->rssi.enabled = feature(FEATURE_RSSI_ADC) || (feature(FEATURE_RX_SPI) && rxConfig()->rx_spi_protocol == RX_SPI_FRSKY_D);
|
||||
adcConfigMutable()->rssi.enabled = feature(FEATURE_RSSI_ADC);
|
||||
#ifdef USE_RX_SPI
|
||||
adcConfigMutable()->rssi.enabled |= (feature(FEATURE_RX_SPI) && rxSpiConfig()->rx_spi_protocol == RX_SPI_FRSKY_D);
|
||||
#endif
|
||||
adcInit(adcConfig());
|
||||
#endif
|
||||
|
||||
|
|
|
@ -127,6 +127,7 @@ extern uint8_t __config_end;
|
|||
#include "pg/pg.h"
|
||||
#include "pg/pg_ids.h"
|
||||
#include "pg/rx.h"
|
||||
#include "pg/rx_spi.h"
|
||||
#include "pg/rx_pwm.h"
|
||||
#include "pg/timerio.h"
|
||||
#include "pg/usb.h"
|
||||
|
@ -2404,10 +2405,10 @@ static void cliBeeper(char *cmdline)
|
|||
}
|
||||
#endif
|
||||
|
||||
#ifdef USE_RX_FRSKY_SPI
|
||||
void cliFrSkyBind(char *cmdline){
|
||||
UNUSED(cmdline);
|
||||
switch (rxConfig()->rx_spi_protocol) {
|
||||
#ifdef USE_RX_FRSKY_SPI
|
||||
switch (rxSpiConfig()->rx_spi_protocol) {
|
||||
case RX_SPI_FRSKY_D:
|
||||
case RX_SPI_FRSKY_X:
|
||||
frSkySpiBind();
|
||||
|
@ -2415,13 +2416,13 @@ void cliFrSkyBind(char *cmdline){
|
|||
cliPrint("Binding...");
|
||||
|
||||
break;
|
||||
#endif
|
||||
default:
|
||||
cliPrint("Not supported.");
|
||||
|
||||
break;
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
static void printMap(uint8_t dumpMask, const rxConfig_t *rxConfig, const rxConfig_t *defaultRxConfig)
|
||||
{
|
||||
|
@ -3591,6 +3592,9 @@ const cliResourceValue_t resourceTable[] = {
|
|||
DEFA( OWNER_SPI_PREINIT_IPU, PG_SPI_PREINIT_IPU_CONFIG, spiCs_t, csnTag, SPI_PREINIT_IPU_COUNT ),
|
||||
DEFA( OWNER_SPI_PREINIT_OPU, PG_SPI_PREINIT_OPU_CONFIG, spiCs_t, csnTag, SPI_PREINIT_OPU_COUNT ),
|
||||
#endif
|
||||
#ifdef USE_RX_SPI
|
||||
DEFS( OWNER_RX_SPI_CS, PG_RX_SPI_CONFIG, rxSpiConfig_t, csnTag ),
|
||||
#endif
|
||||
};
|
||||
|
||||
#undef DEFS
|
||||
|
|
|
@ -45,6 +45,7 @@
|
|||
#include "pg/pg_ids.h"
|
||||
#include "pg/beeper.h"
|
||||
#include "pg/rx.h"
|
||||
#include "pg/rx_spi.h"
|
||||
|
||||
#include "drivers/accgyro/accgyro.h"
|
||||
#include "drivers/bus_i2c.h"
|
||||
|
@ -1054,9 +1055,15 @@ static bool mspProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst)
|
|||
sbufWriteU8(dst, rxConfig()->rcInterpolation);
|
||||
sbufWriteU8(dst, rxConfig()->rcInterpolationInterval);
|
||||
sbufWriteU16(dst, rxConfig()->airModeActivateThreshold * 10 + 1000);
|
||||
sbufWriteU8(dst, rxConfig()->rx_spi_protocol);
|
||||
sbufWriteU32(dst, rxConfig()->rx_spi_id);
|
||||
sbufWriteU8(dst, rxConfig()->rx_spi_rf_channel_count);
|
||||
#ifdef USE_RX_SPI
|
||||
sbufWriteU8(dst, rxSpiConfig()->rx_spi_protocol);
|
||||
sbufWriteU32(dst, rxSpiConfig()->rx_spi_id);
|
||||
sbufWriteU8(dst, rxSpiConfig()->rx_spi_rf_channel_count);
|
||||
#else
|
||||
sbufWriteU8(dst, 0);
|
||||
sbufWriteU32(dst, 0);
|
||||
sbufWriteU8(dst, 0);
|
||||
#endif
|
||||
sbufWriteU8(dst, rxConfig()->fpvCamAngleDegrees);
|
||||
break;
|
||||
|
||||
|
@ -1894,9 +1901,15 @@ static mspResult_e mspProcessInCommand(uint8_t cmdMSP, sbuf_t *src)
|
|||
rxConfigMutable()->airModeActivateThreshold = (sbufReadU16(src) - 1000) / 10;
|
||||
}
|
||||
if (sbufBytesRemaining(src) >= 6) {
|
||||
rxConfigMutable()->rx_spi_protocol = sbufReadU8(src);
|
||||
rxConfigMutable()->rx_spi_id = sbufReadU32(src);
|
||||
rxConfigMutable()->rx_spi_rf_channel_count = sbufReadU8(src);
|
||||
#ifdef USE_RX_SPI
|
||||
rxSpiConfigMutable()->rx_spi_protocol = sbufReadU8(src);
|
||||
rxSpiConfigMutable()->rx_spi_id = sbufReadU32(src);
|
||||
rxSpiConfigMutable()->rx_spi_rf_channel_count = sbufReadU8(src);
|
||||
#else
|
||||
sbufReadU8(src);
|
||||
sbufReadU32(src);
|
||||
sbufReadU8(src);
|
||||
#endif
|
||||
}
|
||||
if (sbufBytesRemaining(src) >= 1) {
|
||||
rxConfigMutable()->fpvCamAngleDegrees = sbufReadU8(src);
|
||||
|
|
|
@ -76,6 +76,7 @@
|
|||
#include "pg/pinio.h"
|
||||
#include "pg/piniobox.h"
|
||||
#include "pg/rx.h"
|
||||
#include "pg/rx_spi.h"
|
||||
#include "pg/rx_pwm.h"
|
||||
#include "pg/sdcard.h"
|
||||
#include "pg/vcd.h"
|
||||
|
@ -531,7 +532,8 @@ const clivalue_t valueTable[] = {
|
|||
{ "rx_max_usec", VAR_UINT16 | MASTER_VALUE, .config.minmax = { PWM_PULSE_MIN, PWM_PULSE_MAX }, PG_RX_CONFIG, offsetof(rxConfig_t, rx_max_usec) },
|
||||
{ "serialrx_halfduplex", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_RX_CONFIG, offsetof(rxConfig_t, halfDuplex) },
|
||||
#ifdef USE_RX_SPI
|
||||
{ "rx_spi_protocol", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_RX_SPI }, PG_RX_CONFIG, offsetof(rxConfig_t, rx_spi_protocol) },
|
||||
{ "rx_spi_protocol", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_RX_SPI }, PG_RX_SPI_CONFIG, offsetof(rxSpiConfig_t, rx_spi_protocol) },
|
||||
{ "rx_spi_bus", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, SPIDEV_COUNT }, PG_RX_SPI_CONFIG, offsetof(rxSpiConfig_t, spibus) },
|
||||
#endif
|
||||
|
||||
// PG_ADC_CONFIG
|
||||
|
|
|
@ -131,7 +131,8 @@
|
|||
#define PG_TIMER_IO_CONFIG 534 // used to store the index for timer use in timerHardware array in target.c
|
||||
#define PG_SPI_PREINIT_IPU_CONFIG 535
|
||||
#define PG_SPI_PREINIT_OPU_CONFIG 536
|
||||
#define PG_BETAFLIGHT_END 536
|
||||
#define PG_RX_SPI_CONFIG 537
|
||||
#define PG_BETAFLIGHT_END 537
|
||||
|
||||
|
||||
// OSD configuration (subject to change)
|
||||
|
|
|
@ -39,7 +39,6 @@ void pgResetFn_rxConfig(rxConfig_t *rxConfig)
|
|||
RESET_CONFIG_2(rxConfig_t, rxConfig,
|
||||
.halfDuplex = 0,
|
||||
.serialrx_provider = SERIALRX_PROVIDER,
|
||||
.rx_spi_protocol = RX_SPI_DEFAULT_PROTOCOL,
|
||||
.serialrx_inverted = 0,
|
||||
.spektrum_bind_pin_override_ioTag = IO_TAG(SPEKTRUM_BIND_PIN),
|
||||
.spektrum_bind_plug_ioTag = IO_TAG(BINDPLUG_PIN),
|
||||
|
|
|
@ -29,10 +29,6 @@ typedef struct rxConfig_s {
|
|||
uint8_t serialrx_provider; // type of UART-based receiver (0 = spek 10, 1 = spek 11, 2 = sbus). Must be enabled by FEATURE_RX_SERIAL first.
|
||||
uint8_t serialrx_inverted; // invert the serial RX protocol compared to it's default setting
|
||||
uint8_t halfDuplex; // allow rx to operate in half duplex mode on F4, ignored for F1 and F3.
|
||||
uint8_t rx_spi_protocol; // type of SPI RX protocol
|
||||
// nrf24: 0 = v202 250kbps. (Must be enabled by FEATURE_RX_NRF24 first.)
|
||||
uint32_t rx_spi_id;
|
||||
uint8_t rx_spi_rf_channel_count;
|
||||
ioTag_t spektrum_bind_pin_override_ioTag;
|
||||
ioTag_t spektrum_bind_plug_ioTag;
|
||||
uint8_t spektrum_sat_bind; // number of bind pulses for Spektrum satellite receivers
|
||||
|
|
44
src/main/pg/rx_spi.c
Normal file
44
src/main/pg/rx_spi.c
Normal file
|
@ -0,0 +1,44 @@
|
|||
/*
|
||||
* This file is part of Cleanflight and Betaflight.
|
||||
*
|
||||
* Cleanflight and Betaflight are free software. You can redistribute
|
||||
* this software and/or modify this software 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.
|
||||
*
|
||||
* Cleanflight and Betaflight are distributed in the hope that they
|
||||
* 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 software.
|
||||
*
|
||||
* If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
#ifdef USE_RX_SPI
|
||||
|
||||
#include "drivers/io.h"
|
||||
#include "drivers/bus_spi.h"
|
||||
|
||||
#include "pg/pg.h"
|
||||
#include "pg/pg_ids.h"
|
||||
#include "pg/rx_spi.h"
|
||||
|
||||
#include "rx/rx_spi.h"
|
||||
|
||||
PG_REGISTER_WITH_RESET_FN(rxSpiConfig_t, rxSpiConfig, PG_RX_SPI_CONFIG, 0);
|
||||
|
||||
void pgResetFn_rxSpiConfig(rxSpiConfig_t *rxSpiConfig)
|
||||
{
|
||||
rxSpiConfig->rx_spi_protocol = RX_SPI_DEFAULT_PROTOCOL;
|
||||
|
||||
// Basic SPI
|
||||
rxSpiConfig->csnTag = IO_TAG(RX_NSS_PIN);
|
||||
rxSpiConfig->spibus = SPI_DEV_TO_CFG(spiDeviceByInstance(RX_SPI_INSTANCE));
|
||||
}
|
||||
#endif
|
40
src/main/pg/rx_spi.h
Normal file
40
src/main/pg/rx_spi.h
Normal file
|
@ -0,0 +1,40 @@
|
|||
/*
|
||||
* This file is part of Cleanflight and Betaflight.
|
||||
*
|
||||
* Cleanflight and Betaflight are free software. You can redistribute
|
||||
* this software and/or modify this software 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.
|
||||
*
|
||||
* Cleanflight and Betaflight are distributed in the hope that they
|
||||
* 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 software.
|
||||
*
|
||||
* If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#include "drivers/io_types.h"
|
||||
|
||||
#include "pg/pg.h"
|
||||
|
||||
typedef struct rxSpiConfig_s {
|
||||
// RX protocol
|
||||
uint8_t rx_spi_protocol; // type of SPI RX protocol
|
||||
// nrf24: 0 = v202 250kbps. (Must be enabled by FEATURE_RX_NRF24 first.)
|
||||
uint32_t rx_spi_id;
|
||||
uint8_t rx_spi_rf_channel_count;
|
||||
|
||||
// SPI Bus
|
||||
ioTag_t csnTag;
|
||||
uint8_t spibus;
|
||||
|
||||
} rxSpiConfig_t;
|
||||
|
||||
PG_DECLARE(rxSpiConfig_t, rxSpiConfig);
|
|
@ -35,7 +35,7 @@ typedef struct rxFrSkySpiConfig_s {
|
|||
|
||||
PG_DECLARE(rxFrSkySpiConfig_t, rxFrSkySpiConfig);
|
||||
|
||||
bool frSkySpiInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig);
|
||||
bool frSkySpiInit(const rxSpiConfig_t *rxSpiConfig, rxRuntimeConfig_t *rxRuntimeConfig);
|
||||
rx_spi_received_e frSkySpiDataReceived(uint8_t *packet);
|
||||
void frSkySpiSetRcData(uint16_t *rcData, const uint8_t *payload);
|
||||
|
||||
|
|
|
@ -31,6 +31,7 @@
|
|||
#include "build/debug.h"
|
||||
|
||||
#include "pg/rx.h"
|
||||
#include "pg/rx_spi.h"
|
||||
|
||||
#include "common/maths.h"
|
||||
#include "common/utils.h"
|
||||
|
|
|
@ -26,16 +26,17 @@
|
|||
|
||||
#include "common/maths.h"
|
||||
|
||||
#include "pg/pg.h"
|
||||
#include "pg/pg_ids.h"
|
||||
#include "pg/rx.h"
|
||||
#include "pg/rx_spi.h"
|
||||
|
||||
#include "drivers/rx/rx_cc2500.h"
|
||||
#include "drivers/io.h"
|
||||
#include "drivers/time.h"
|
||||
|
||||
#include "fc/config.h"
|
||||
|
||||
#include "pg/pg.h"
|
||||
#include "pg/pg_ids.h"
|
||||
#include "pg/rx.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
#include "rx/rx_spi.h"
|
||||
|
||||
|
@ -513,7 +514,7 @@ static bool frSkySpiDetect(void)
|
|||
return false;
|
||||
}
|
||||
|
||||
bool frSkySpiInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig)
|
||||
bool frSkySpiInit(const rxSpiConfig_t *rxSpiConfig, rxRuntimeConfig_t *rxRuntimeConfig)
|
||||
{
|
||||
#if !defined(RX_FRSKY_SPI_DISABLE_CHIP_DETECTION)
|
||||
if (!frSkySpiDetect()) {
|
||||
|
@ -523,7 +524,7 @@ bool frSkySpiInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig
|
|||
UNUSED(frSkySpiDetect);
|
||||
#endif
|
||||
|
||||
spiProtocol = rxConfig->rx_spi_protocol;
|
||||
spiProtocol = rxSpiConfig->rx_spi_protocol;
|
||||
|
||||
switch (spiProtocol) {
|
||||
case RX_SPI_FRSKY_D:
|
||||
|
|
|
@ -29,6 +29,7 @@
|
|||
#include "build/debug.h"
|
||||
|
||||
#include "pg/rx.h"
|
||||
#include "pg/rx_spi.h"
|
||||
|
||||
#include "common/maths.h"
|
||||
#include "common/utils.h"
|
||||
|
|
|
@ -38,7 +38,7 @@
|
|||
|
||||
#include "pg/pg.h"
|
||||
#include "pg/pg_ids.h"
|
||||
#include "pg/rx.h"
|
||||
#include "pg/rx_spi.h"
|
||||
|
||||
#include "rx/flysky_defs.h"
|
||||
#include "rx/rx.h"
|
||||
|
@ -356,9 +356,9 @@ static rx_spi_received_e flySkyReadAndProcess (uint8_t *payload, const uint32_t
|
|||
return result;
|
||||
}
|
||||
|
||||
bool flySkyInit (const struct rxConfig_s *rxConfig, struct rxRuntimeConfig_s *rxRuntimeConfig)
|
||||
bool flySkyInit (const rxSpiConfig_t *rxSpiConfig, struct rxRuntimeConfig_s *rxRuntimeConfig)
|
||||
{
|
||||
protocol = rxConfig->rx_spi_protocol;
|
||||
protocol = rxSpiConfig->rx_spi_protocol;
|
||||
|
||||
if (protocol != flySkyConfig()->protocol) {
|
||||
PG_RESET(flySkyConfig);
|
||||
|
|
|
@ -31,8 +31,8 @@ typedef struct flySkyConfig_s {
|
|||
|
||||
PG_DECLARE(flySkyConfig_t, flySkyConfig);
|
||||
|
||||
struct rxConfig_s;
|
||||
struct rxSpiConfig_s;
|
||||
struct rxRuntimeConfig_s;
|
||||
bool flySkyInit(const struct rxConfig_s *rxConfig, struct rxRuntimeConfig_s *rxRuntimeConfig);
|
||||
bool flySkyInit(const struct rxSpiConfig_s *rxConfig, struct rxRuntimeConfig_s *rxRuntimeConfig);
|
||||
void flySkySetRcDataFromPayload(uint16_t *rcData, const uint8_t *payload);
|
||||
rx_spi_received_e flySkyDataReceived(uint8_t *payload);
|
||||
|
|
|
@ -299,10 +299,10 @@ static void cx10Nrf24Setup(rx_spi_protocol_e protocol)
|
|||
NRF24L01_SetRxMode(); // enter receive mode to start listening for packets
|
||||
}
|
||||
|
||||
bool cx10Nrf24Init(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig)
|
||||
bool cx10Nrf24Init(const rxSpiConfig_t *rxSpiConfig, rxRuntimeConfig_t *rxRuntimeConfig)
|
||||
{
|
||||
rxRuntimeConfig->channelCount = RC_CHANNEL_COUNT;
|
||||
cx10Nrf24Setup((rx_spi_protocol_e)rxConfig->rx_spi_protocol);
|
||||
cx10Nrf24Setup((rx_spi_protocol_e)rxSpiConfig->rx_spi_protocol);
|
||||
|
||||
return true;
|
||||
}
|
||||
|
|
|
@ -23,8 +23,8 @@
|
|||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
|
||||
struct rxConfig_s;
|
||||
struct rxSpiConfig_s;
|
||||
struct rxRuntimeConfig_s;
|
||||
bool cx10Nrf24Init(const struct rxConfig_s *rxConfig, struct rxRuntimeConfig_s *rxRuntimeConfig);
|
||||
bool cx10Nrf24Init(const struct rxSpiConfig_s *rxSpiConfig, struct rxRuntimeConfig_s *rxRuntimeConfig);
|
||||
void cx10Nrf24SetRcDataFromPayload(uint16_t *rcData, const uint8_t *payload);
|
||||
rx_spi_received_e cx10Nrf24DataReceived(uint8_t *payload);
|
||||
|
|
|
@ -283,10 +283,10 @@ static void h8_3dNrf24Setup(rx_spi_protocol_e protocol, const uint32_t *rxSpiId)
|
|||
NRF24L01_SetRxMode(); // enter receive mode to start listening for packets
|
||||
}
|
||||
|
||||
bool h8_3dNrf24Init(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig)
|
||||
bool h8_3dNrf24Init(const rxSpiConfig_t *rxSpiConfig, rxRuntimeConfig_t *rxRuntimeConfig)
|
||||
{
|
||||
rxRuntimeConfig->channelCount = RC_CHANNEL_COUNT;
|
||||
h8_3dNrf24Setup((rx_spi_protocol_e)rxConfig->rx_spi_protocol, &rxConfig->rx_spi_id);
|
||||
h8_3dNrf24Setup((rx_spi_protocol_e)rxSpiConfig->rx_spi_protocol, &rxSpiConfig->rx_spi_id);
|
||||
|
||||
return true;
|
||||
}
|
||||
|
|
|
@ -23,8 +23,8 @@
|
|||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
|
||||
struct rxConfig_s;
|
||||
struct rxSpiConfig_s;
|
||||
struct rxRuntimeConfig_s;
|
||||
bool h8_3dNrf24Init(const struct rxConfig_s *rxConfig, struct rxRuntimeConfig_s *rxRuntimeConfig);
|
||||
bool h8_3dNrf24Init(const struct rxSpiConfig_s *rxSpiConfig, struct rxRuntimeConfig_s *rxRuntimeConfig);
|
||||
void h8_3dNrf24SetRcDataFromPayload(uint16_t *rcData, const uint8_t *payload);
|
||||
rx_spi_received_e h8_3dNrf24DataReceived(uint8_t *payload);
|
||||
|
|
|
@ -424,10 +424,10 @@ static void inavNrf24Setup(rx_spi_protocol_e protocol, const uint32_t *rxSpiId,
|
|||
writeAckPayload(ackPayload, payloadSize);
|
||||
}
|
||||
|
||||
bool inavNrf24Init(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig)
|
||||
bool inavNrf24Init(const rxSpiConfig_t *rxSpiConfig, rxRuntimeConfig_t *rxRuntimeConfig)
|
||||
{
|
||||
rxRuntimeConfig->channelCount = RC_CHANNEL_COUNT_MAX;
|
||||
inavNrf24Setup((rx_spi_protocol_e)rxConfig->rx_spi_protocol, &rxConfig->rx_spi_id, rxConfig->rx_spi_rf_channel_count);
|
||||
inavNrf24Setup((rx_spi_protocol_e)rxSpiConfig->rx_spi_protocol, &rxSpiConfig->rx_spi_id, rxSpiConfig->rx_spi_rf_channel_count);
|
||||
|
||||
return true;
|
||||
}
|
||||
|
|
|
@ -23,9 +23,9 @@
|
|||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
|
||||
struct rxConfig_s;
|
||||
struct rxSpiConfig_s;
|
||||
struct rxRuntimeConfig_s;
|
||||
bool inavNrf24Init(const struct rxConfig_s *rxConfig, struct rxRuntimeConfig_s *rxRuntimeConfig);
|
||||
bool inavNrf24Init(const struct rxSpiConfig_s *rxSpiConfig, struct rxRuntimeConfig_s *rxRuntimeConfig);
|
||||
void inavNrf24SetRcDataFromPayload(uint16_t *rcData, const uint8_t *payload);
|
||||
rx_spi_received_e inavNrf24DataReceived(uint8_t *payload);
|
||||
|
||||
|
|
|
@ -299,10 +299,10 @@ static void symaNrf24Setup(rx_spi_protocol_e protocol)
|
|||
NRF24L01_SetRxMode(); // enter receive mode to start listening for packets
|
||||
}
|
||||
|
||||
bool symaNrf24Init(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig)
|
||||
bool symaNrf24Init(const rxSpiConfig_t *rxSpiConfig, rxRuntimeConfig_t *rxRuntimeConfig)
|
||||
{
|
||||
rxRuntimeConfig->channelCount = RC_CHANNEL_COUNT;
|
||||
symaNrf24Setup((rx_spi_protocol_e)rxConfig->rx_spi_protocol);
|
||||
symaNrf24Setup((rx_spi_protocol_e)rxSpiConfig->rx_spi_protocol);
|
||||
|
||||
return true;
|
||||
}
|
||||
|
|
|
@ -23,9 +23,9 @@
|
|||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
|
||||
struct rxConfig_s;
|
||||
struct rxSpiConfig_s;
|
||||
struct rxRuntimeConfig_s;
|
||||
bool symaNrf24Init(const struct rxConfig_s *rxConfig, struct rxRuntimeConfig_s *rxRuntimeConfig);
|
||||
bool symaNrf24Init(const struct rxSpiConfig_s *rxSpiConfig, struct rxRuntimeConfig_s *rxRuntimeConfig);
|
||||
void symaNrf24SetRcDataFromPayload(uint16_t *rcData, const uint8_t *payload);
|
||||
rx_spi_received_e symaNrf24DataReceived(uint8_t *payload);
|
||||
|
||||
|
|
|
@ -259,10 +259,10 @@ static void v202Nrf24Setup(rx_spi_protocol_e protocol)
|
|||
NRF24L01_SetRxMode(); // enter receive mode to start listening for packets
|
||||
}
|
||||
|
||||
bool v202Nrf24Init(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig)
|
||||
bool v202Nrf24Init(const rxSpiConfig_t *rxSpiConfig, rxRuntimeConfig_t *rxRuntimeConfig)
|
||||
{
|
||||
rxRuntimeConfig->channelCount = V2X2_RC_CHANNEL_COUNT;
|
||||
v202Nrf24Setup((rx_spi_protocol_e)rxConfig->rx_spi_protocol);
|
||||
v202Nrf24Setup((rx_spi_protocol_e)rxSpiConfig->rx_spi_protocol);
|
||||
|
||||
return true;
|
||||
}
|
||||
|
|
|
@ -23,8 +23,8 @@
|
|||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
|
||||
struct rxConfig_s;
|
||||
struct rxSpiConfig_s;
|
||||
struct rxRuntimeConfig_s;
|
||||
bool v202Nrf24Init(const struct rxConfig_s *rxConfig, struct rxRuntimeConfig_s *rxRuntimeConfig);
|
||||
bool v202Nrf24Init(const struct rxSpiConfig_s *rxSpiConfig, struct rxRuntimeConfig_s *rxRuntimeConfig);
|
||||
void v202Nrf24SetRcDataFromPayload(uint16_t *rcData, const uint8_t *payload);
|
||||
rx_spi_received_e v202Nrf24DataReceived(uint8_t *payload);
|
||||
|
|
|
@ -285,7 +285,7 @@ void rxInit(void)
|
|||
|
||||
#ifdef USE_RX_SPI
|
||||
if (feature(FEATURE_RX_SPI)) {
|
||||
const bool enabled = rxSpiInit(rxConfig(), &rxRuntimeConfig);
|
||||
const bool enabled = rxSpiInit(rxSpiConfig(), &rxRuntimeConfig);
|
||||
if (!enabled) {
|
||||
featureClear(FEATURE_RX_SPI);
|
||||
rxRuntimeConfig.rcReadRawFn = nullReadRawRC;
|
||||
|
|
|
@ -23,6 +23,7 @@
|
|||
#include "common/time.h"
|
||||
|
||||
#include "pg/pg.h"
|
||||
#include "pg/rx.h"
|
||||
|
||||
#include "drivers/io_types.h"
|
||||
|
||||
|
|
|
@ -30,14 +30,14 @@
|
|||
#include "common/utils.h"
|
||||
|
||||
#include "config/feature.h"
|
||||
#include "pg/rx.h"
|
||||
|
||||
#include "drivers/rx/rx_spi.h"
|
||||
#include "drivers/rx/rx_nrf24l01.h"
|
||||
|
||||
#include "fc/config.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
#include "pg/rx_spi.h"
|
||||
|
||||
#include "rx/rx_spi.h"
|
||||
#include "rx/cc2500_frsky_common.h"
|
||||
#include "rx/nrf24_cx10.h"
|
||||
|
@ -53,7 +53,7 @@ uint16_t rxSpiRcData[MAX_SUPPORTED_RC_CHANNEL_COUNT];
|
|||
STATIC_UNIT_TESTED uint8_t rxSpiPayload[RX_SPI_MAX_PAYLOAD_SIZE];
|
||||
STATIC_UNIT_TESTED uint8_t rxSpiNewPacketAvailable; // set true when a new packet is received
|
||||
|
||||
typedef bool (*protocolInitFnPtr)(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig);
|
||||
typedef bool (*protocolInitFnPtr)(const rxSpiConfig_t *rxSpiConfig, rxRuntimeConfig_t *rxRuntimeConfig);
|
||||
typedef rx_spi_received_e (*protocolDataReceivedFnPtr)(uint8_t *payload);
|
||||
typedef void (*protocolSetRcDataFromPayloadFnPtr)(uint16_t *rcData, const uint8_t *payload);
|
||||
|
||||
|
@ -168,13 +168,16 @@ static uint8_t rxSpiFrameStatus(rxRuntimeConfig_t *rxRuntimeConfig)
|
|||
/*
|
||||
* Set and initialize the RX protocol
|
||||
*/
|
||||
bool rxSpiInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig)
|
||||
bool rxSpiInit(const rxSpiConfig_t *rxSpiConfig, rxRuntimeConfig_t *rxRuntimeConfig)
|
||||
{
|
||||
bool ret = false;
|
||||
|
||||
rxSpiDeviceInit();
|
||||
if (rxSpiSetProtocol(rxConfig->rx_spi_protocol)) {
|
||||
ret = protocolInit(rxConfig, rxRuntimeConfig);
|
||||
if (!rxSpiDeviceInit(rxSpiConfig)) {
|
||||
return false;
|
||||
}
|
||||
|
||||
if (rxSpiSetProtocol(rxSpiConfig->rx_spi_protocol)) {
|
||||
ret = protocolInit(rxSpiConfig, rxRuntimeConfig);
|
||||
}
|
||||
rxSpiNewPacketAvailable = false;
|
||||
rxRuntimeConfig->rxRefreshRate = 20000;
|
||||
|
|
|
@ -22,6 +22,7 @@
|
|||
|
||||
#include "pg/rx.h"
|
||||
#include "rx/rx.h"
|
||||
#include "pg/rx_spi.h"
|
||||
|
||||
// Used in MSP. Append at end.
|
||||
typedef enum {
|
||||
|
@ -77,4 +78,4 @@ typedef enum {
|
|||
#define RC_CHANNEL_HEADLESS RC_SPI_AUX5
|
||||
#define RC_CHANNEL_RTH RC_SPI_AUX6 // return to home
|
||||
|
||||
bool rxSpiInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig);
|
||||
bool rxSpiInit(const rxSpiConfig_t *rxSpiConfig, rxRuntimeConfig_t *rxRuntimeConfig);
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue