Merge pull request #3300 from jflyper/bfdev-configurable-bind-pin-2
Automatic/configurable spektrum bind facility
This commit is contained in:
commit
4bacbdcc91
|
@ -63,5 +63,6 @@ const char * const ownerNames[OWNER_TOTAL_COUNT] = {
|
||||||
"VTX",
|
"VTX",
|
||||||
"COMPASS_CS",
|
"COMPASS_CS",
|
||||||
"SPI_PREINIT",
|
"SPI_PREINIT",
|
||||||
|
"RX_BIND_PLUG",
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|
|
@ -63,6 +63,7 @@ typedef enum {
|
||||||
OWNER_VTX,
|
OWNER_VTX,
|
||||||
OWNER_COMPASS_CS,
|
OWNER_COMPASS_CS,
|
||||||
OWNER_SPI_PREINIT,
|
OWNER_SPI_PREINIT,
|
||||||
|
OWNER_RX_BIND_PLUG,
|
||||||
OWNER_TOTAL_COUNT
|
OWNER_TOTAL_COUNT
|
||||||
} resourceOwner_e;
|
} resourceOwner_e;
|
||||||
|
|
||||||
|
|
|
@ -18,6 +18,7 @@
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
#include "drivers/io.h"
|
#include "drivers/io.h"
|
||||||
|
#include "config/parameter_group.h"
|
||||||
|
|
||||||
typedef enum portMode_t {
|
typedef enum portMode_t {
|
||||||
MODE_RX = 1 << 0,
|
MODE_RX = 1 << 0,
|
||||||
|
@ -86,6 +87,8 @@ typedef struct serialPinConfig_s {
|
||||||
ioTag_t ioTagInverter[SERIAL_PORT_MAX_INDEX];
|
ioTag_t ioTagInverter[SERIAL_PORT_MAX_INDEX];
|
||||||
} serialPinConfig_t;
|
} serialPinConfig_t;
|
||||||
|
|
||||||
|
PG_DECLARE(serialPinConfig_t, serialPinConfig);
|
||||||
|
|
||||||
struct serialPortVTable {
|
struct serialPortVTable {
|
||||||
void (*serialWrite)(serialPort_t *instance, uint8_t ch);
|
void (*serialWrite)(serialPort_t *instance, uint8_t ch);
|
||||||
|
|
||||||
|
|
|
@ -2828,6 +2828,10 @@ const cliResourceValue_t resourceTable[] = {
|
||||||
{ OWNER_I2C_SDA, PG_I2C_CONFIG, offsetof(i2cConfig_t, ioTagSda[0]), I2CDEV_COUNT },
|
{ OWNER_I2C_SDA, PG_I2C_CONFIG, offsetof(i2cConfig_t, ioTagSda[0]), I2CDEV_COUNT },
|
||||||
#endif
|
#endif
|
||||||
{ OWNER_LED, PG_STATUS_LED_CONFIG, offsetof(statusLedConfig_t, ioTags[0]), STATUS_LED_NUMBER },
|
{ OWNER_LED, PG_STATUS_LED_CONFIG, offsetof(statusLedConfig_t, ioTags[0]), STATUS_LED_NUMBER },
|
||||||
|
#ifdef USE_SPEKTRUM_BIND
|
||||||
|
{ OWNER_RX_BIND, PG_RX_CONFIG, offsetof(rxConfig_t, spektrum_bind_pin_override_ioTag), 0 },
|
||||||
|
{ OWNER_RX_BIND_PLUG, PG_RX_CONFIG, offsetof(rxConfig_t, spektrum_bind_plug_ioTag), 0 },
|
||||||
|
#endif
|
||||||
};
|
};
|
||||||
|
|
||||||
static ioTag_t *getIoTag(const cliResourceValue_t value, uint8_t index)
|
static ioTag_t *getIoTag(const cliResourceValue_t value, uint8_t index)
|
||||||
|
|
|
@ -91,7 +91,6 @@ PG_DECLARE(ppmConfig_t, ppmConfig);
|
||||||
PG_DECLARE(pwmConfig_t, pwmConfig);
|
PG_DECLARE(pwmConfig_t, pwmConfig);
|
||||||
PG_DECLARE(vcdProfile_t, vcdProfile);
|
PG_DECLARE(vcdProfile_t, vcdProfile);
|
||||||
PG_DECLARE(sdcardConfig_t, sdcardConfig);
|
PG_DECLARE(sdcardConfig_t, sdcardConfig);
|
||||||
PG_DECLARE(serialPinConfig_t, serialPinConfig);
|
|
||||||
|
|
||||||
struct pidProfile_s;
|
struct pidProfile_s;
|
||||||
extern struct pidProfile_s *currentPidProfile;
|
extern struct pidProfile_s *currentPidProfile;
|
||||||
|
|
|
@ -315,11 +315,12 @@ void init(void)
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef SPEKTRUM_BIND_PIN
|
#if defined(USE_SPEKTRUM_BIND) && !defined(SITL)
|
||||||
if (feature(FEATURE_RX_SERIAL)) {
|
if (feature(FEATURE_RX_SERIAL)) {
|
||||||
switch (rxConfig()->serialrx_provider) {
|
switch (rxConfig()->serialrx_provider) {
|
||||||
case SERIALRX_SPEKTRUM1024:
|
case SERIALRX_SPEKTRUM1024:
|
||||||
case SERIALRX_SPEKTRUM2048:
|
case SERIALRX_SPEKTRUM2048:
|
||||||
|
case SERIALRX_SRXL:
|
||||||
// Spektrum satellite binding if enabled on startup.
|
// Spektrum satellite binding if enabled on startup.
|
||||||
// Must be called before that 100ms sleep so that we don't lose satellite's binding window after startup.
|
// Must be called before that 100ms sleep so that we don't lose satellite's binding window after startup.
|
||||||
// The rest of Spektrum initialization will happen later - via spektrumInit()
|
// The rest of Spektrum initialization will happen later - via spektrumInit()
|
||||||
|
|
|
@ -357,7 +357,7 @@ const clivalue_t valueTable[] = {
|
||||||
{ "serialrx_provider", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_SERIAL_RX }, PG_RX_CONFIG, offsetof(rxConfig_t, serialrx_provider) },
|
{ "serialrx_provider", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_SERIAL_RX }, PG_RX_CONFIG, offsetof(rxConfig_t, serialrx_provider) },
|
||||||
{ "sbus_inversion", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_RX_CONFIG, offsetof(rxConfig_t, sbus_inversion) },
|
{ "sbus_inversion", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_RX_CONFIG, offsetof(rxConfig_t, sbus_inversion) },
|
||||||
#endif
|
#endif
|
||||||
#ifdef SPEKTRUM_BIND_PIN
|
#ifdef USE_SPEKTRUM_BIND
|
||||||
{ "spektrum_sat_bind", VAR_UINT8 | MASTER_VALUE, .config.minmax = { SPEKTRUM_SAT_BIND_DISABLED, SPEKTRUM_SAT_BIND_MAX}, PG_RX_CONFIG, offsetof(rxConfig_t, spektrum_sat_bind) },
|
{ "spektrum_sat_bind", VAR_UINT8 | MASTER_VALUE, .config.minmax = { SPEKTRUM_SAT_BIND_DISABLED, SPEKTRUM_SAT_BIND_MAX}, PG_RX_CONFIG, offsetof(rxConfig_t, spektrum_sat_bind) },
|
||||||
{ "spektrum_sat_bind_autoreset",VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, 1 }, PG_RX_CONFIG, offsetof(rxConfig_t, spektrum_sat_bind_autoreset) },
|
{ "spektrum_sat_bind_autoreset",VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, 1 }, PG_RX_CONFIG, offsetof(rxConfig_t, spektrum_sat_bind_autoreset) },
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -24,6 +24,7 @@
|
||||||
|
|
||||||
#include "common/utils.h"
|
#include "common/utils.h"
|
||||||
|
|
||||||
|
#include "drivers/io.h"
|
||||||
#include "rx/rx.h"
|
#include "rx/rx.h"
|
||||||
#include "rx/msp.h"
|
#include "rx/msp.h"
|
||||||
|
|
||||||
|
|
|
@ -28,6 +28,7 @@
|
||||||
|
|
||||||
#include "build/build_config.h"
|
#include "build/build_config.h"
|
||||||
|
|
||||||
|
#include "drivers/io.h"
|
||||||
#include "drivers/rx_nrf24l01.h"
|
#include "drivers/rx_nrf24l01.h"
|
||||||
#include "drivers/rx_xn297.h"
|
#include "drivers/rx_xn297.h"
|
||||||
#include "drivers/time.h"
|
#include "drivers/time.h"
|
||||||
|
|
|
@ -30,6 +30,7 @@
|
||||||
|
|
||||||
#include "common/utils.h"
|
#include "common/utils.h"
|
||||||
|
|
||||||
|
#include "drivers/io.h"
|
||||||
#include "drivers/rx_nrf24l01.h"
|
#include "drivers/rx_nrf24l01.h"
|
||||||
#include "drivers/rx_xn297.h"
|
#include "drivers/rx_xn297.h"
|
||||||
#include "drivers/time.h"
|
#include "drivers/time.h"
|
||||||
|
|
|
@ -28,6 +28,7 @@
|
||||||
|
|
||||||
#include "common/utils.h"
|
#include "common/utils.h"
|
||||||
|
|
||||||
|
#include "drivers/io.h"
|
||||||
#include "drivers/rx_nrf24l01.h"
|
#include "drivers/rx_nrf24l01.h"
|
||||||
#include "drivers/time.h"
|
#include "drivers/time.h"
|
||||||
|
|
||||||
|
|
|
@ -28,6 +28,7 @@
|
||||||
|
|
||||||
#include "build/build_config.h"
|
#include "build/build_config.h"
|
||||||
|
|
||||||
|
#include "drivers/io.h"
|
||||||
#include "drivers/rx_nrf24l01.h"
|
#include "drivers/rx_nrf24l01.h"
|
||||||
#include "drivers/time.h"
|
#include "drivers/time.h"
|
||||||
|
|
||||||
|
|
|
@ -30,6 +30,7 @@
|
||||||
|
|
||||||
#include "common/utils.h"
|
#include "common/utils.h"
|
||||||
|
|
||||||
|
#include "drivers/io.h"
|
||||||
#include "drivers/rx_nrf24l01.h"
|
#include "drivers/rx_nrf24l01.h"
|
||||||
#include "drivers/time.h"
|
#include "drivers/time.h"
|
||||||
|
|
||||||
|
|
|
@ -108,6 +108,14 @@ static uint8_t rcSampleIndex = 0;
|
||||||
#define RX_MAX_USEC 2115
|
#define RX_MAX_USEC 2115
|
||||||
#define RX_MID_USEC 1500
|
#define RX_MID_USEC 1500
|
||||||
|
|
||||||
|
#ifndef SPEKTRUM_BIND_PIN
|
||||||
|
#define SPEKTRUM_BIND_PIN NONE
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifndef BINDPLUG_PIN
|
||||||
|
#define BINDPLUG_PIN NONE
|
||||||
|
#endif
|
||||||
|
|
||||||
PG_REGISTER_WITH_RESET_FN(rxConfig_t, rxConfig, PG_RX_CONFIG, 0);
|
PG_REGISTER_WITH_RESET_FN(rxConfig_t, rxConfig, PG_RX_CONFIG, 0);
|
||||||
void pgResetFn_rxConfig(rxConfig_t *rxConfig)
|
void pgResetFn_rxConfig(rxConfig_t *rxConfig)
|
||||||
{
|
{
|
||||||
|
@ -116,6 +124,8 @@ void pgResetFn_rxConfig(rxConfig_t *rxConfig)
|
||||||
.serialrx_provider = SERIALRX_PROVIDER,
|
.serialrx_provider = SERIALRX_PROVIDER,
|
||||||
.rx_spi_protocol = RX_SPI_DEFAULT_PROTOCOL,
|
.rx_spi_protocol = RX_SPI_DEFAULT_PROTOCOL,
|
||||||
.sbus_inversion = 1,
|
.sbus_inversion = 1,
|
||||||
|
.spektrum_bind_pin_override_ioTag = IO_TAG(SPEKTRUM_BIND_PIN),
|
||||||
|
.spektrum_bind_plug_ioTag = IO_TAG(BINDPLUG_PIN),
|
||||||
.spektrum_sat_bind = 0,
|
.spektrum_sat_bind = 0,
|
||||||
.spektrum_sat_bind_autoreset = 1,
|
.spektrum_sat_bind_autoreset = 1,
|
||||||
.midrc = RX_MID_USEC,
|
.midrc = RX_MID_USEC,
|
||||||
|
|
|
@ -122,6 +122,8 @@ typedef struct rxConfig_s {
|
||||||
uint8_t rx_spi_protocol; // type of nrf24 protocol (0 = v202 250kbps). Must be enabled by FEATURE_RX_NRF24 first.
|
uint8_t rx_spi_protocol; // type of nrf24 protocol (0 = v202 250kbps). Must be enabled by FEATURE_RX_NRF24 first.
|
||||||
uint32_t rx_spi_id;
|
uint32_t rx_spi_id;
|
||||||
uint8_t rx_spi_rf_channel_count;
|
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
|
uint8_t spektrum_sat_bind; // number of bind pulses for Spektrum satellite receivers
|
||||||
uint8_t spektrum_sat_bind_autoreset; // whenever we will reset (exit) binding mode after hard reboot
|
uint8_t spektrum_sat_bind_autoreset; // whenever we will reset (exit) binding mode after hard reboot
|
||||||
uint8_t rssi_channel;
|
uint8_t rssi_channel;
|
||||||
|
|
|
@ -77,13 +77,6 @@ static volatile uint8_t spekFrame[SPEK_FRAME_SIZE];
|
||||||
static rxRuntimeConfig_t *rxRuntimeConfigPtr;
|
static rxRuntimeConfig_t *rxRuntimeConfigPtr;
|
||||||
static serialPort_t *serialPort;
|
static serialPort_t *serialPort;
|
||||||
|
|
||||||
#ifdef SPEKTRUM_BIND_PIN
|
|
||||||
static IO_t BindPin = DEFIO_IO(NONE);
|
|
||||||
#ifdef BINDPLUG_PIN
|
|
||||||
static IO_t BindPlug = DEFIO_IO(NONE);
|
|
||||||
#endif
|
|
||||||
#endif
|
|
||||||
|
|
||||||
static uint8_t telemetryBuf[SRXL_FRAME_SIZE_MAX];
|
static uint8_t telemetryBuf[SRXL_FRAME_SIZE_MAX];
|
||||||
static uint8_t telemetryBufLen = 0;
|
static uint8_t telemetryBufLen = 0;
|
||||||
|
|
||||||
|
@ -180,12 +173,14 @@ static uint16_t spektrumReadRawRC(const rxRuntimeConfig_t *rxRuntimeConfig, uint
|
||||||
return data;
|
return data;
|
||||||
}
|
}
|
||||||
|
|
||||||
#ifdef SPEKTRUM_BIND_PIN
|
#ifdef USE_SPEKTRUM_BIND
|
||||||
|
|
||||||
bool spekShouldBind(uint8_t spektrum_sat_bind)
|
bool spekShouldBind(uint8_t spektrum_sat_bind)
|
||||||
{
|
{
|
||||||
#ifdef BINDPLUG_PIN
|
#ifdef USE_SPEKTRUM_BIND_PLUG
|
||||||
BindPlug = IOGetByTag(IO_TAG(BINDPLUG_PIN));
|
IO_t BindPlug = IOGetByTag(rxConfig()->spektrum_bind_plug_ioTag);
|
||||||
|
|
||||||
|
if (BindPlug) {
|
||||||
IOInit(BindPlug, OWNER_RX_BIND, 0);
|
IOInit(BindPlug, OWNER_RX_BIND, 0);
|
||||||
IOConfigGPIO(BindPlug, IOCFG_IPU);
|
IOConfigGPIO(BindPlug, IOCFG_IPU);
|
||||||
|
|
||||||
|
@ -194,6 +189,7 @@ bool spekShouldBind(uint8_t spektrum_sat_bind)
|
||||||
if (IORead(BindPlug)) {
|
if (IORead(BindPlug)) {
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
return !(
|
return !(
|
||||||
|
@ -202,6 +198,7 @@ bool spekShouldBind(uint8_t spektrum_sat_bind)
|
||||||
spektrum_sat_bind > SPEKTRUM_SAT_BIND_MAX
|
spektrum_sat_bind > SPEKTRUM_SAT_BIND_MAX
|
||||||
);
|
);
|
||||||
}
|
}
|
||||||
|
|
||||||
/* spektrumBind function ported from Baseflight. It's used to bind satellite receiver to TX.
|
/* spektrumBind function ported from Baseflight. It's used to bind satellite receiver to TX.
|
||||||
* Function must be called immediately after startup so that we don't miss satellite bind window.
|
* Function must be called immediately after startup so that we don't miss satellite bind window.
|
||||||
* Known parameters. Tested with DSMX satellite and DX8 radio. Framerate (11ms or 22ms) must be selected from TX.
|
* Known parameters. Tested with DSMX satellite and DX8 radio. Framerate (11ms or 22ms) must be selected from TX.
|
||||||
|
@ -210,52 +207,92 @@ bool spekShouldBind(uint8_t spektrum_sat_bind)
|
||||||
*/
|
*/
|
||||||
void spektrumBind(rxConfig_t *rxConfig)
|
void spektrumBind(rxConfig_t *rxConfig)
|
||||||
{
|
{
|
||||||
int i;
|
|
||||||
if (!spekShouldBind(rxConfig->spektrum_sat_bind)) {
|
if (!spekShouldBind(rxConfig->spektrum_sat_bind)) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// Determine a pin to use
|
||||||
|
ioTag_t bindPin;
|
||||||
|
|
||||||
|
if (rxConfig->spektrum_bind_pin_override_ioTag) {
|
||||||
|
bindPin = rxConfig->spektrum_bind_pin_override_ioTag;
|
||||||
|
} else {
|
||||||
|
const serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_RX_SERIAL);
|
||||||
|
if (!portConfig) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
int index = SERIAL_PORT_IDENTIFIER_TO_INDEX(portConfig->identifier);
|
||||||
|
ioTag_t txPin = serialPinConfig()->ioTagTx[index];
|
||||||
|
ioTag_t rxPin = serialPinConfig()->ioTagRx[index];
|
||||||
|
|
||||||
|
// Take care half-duplex case
|
||||||
|
switch (rxConfig->serialrx_provider) {
|
||||||
|
case SERIALRX_SRXL:
|
||||||
|
#ifdef TELEMETRY
|
||||||
|
if (feature(FEATURE_TELEMETRY) && !telemetryCheckRxPortShared(portConfig)) {
|
||||||
|
bindPin = txPin;
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
#endif
|
||||||
|
default:
|
||||||
|
bindPin = rxPin;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (!bindPin) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
IO_t bindIO = IOGetByTag(bindPin);
|
||||||
|
|
||||||
|
IOInit(bindIO, OWNER_RX_BIND, 0);
|
||||||
|
IOConfigGPIO(bindIO, IOCFG_OUT_PP);
|
||||||
|
|
||||||
LED1_ON;
|
LED1_ON;
|
||||||
|
|
||||||
BindPin = IOGetByTag(IO_TAG(SPEKTRUM_BIND_PIN));
|
|
||||||
IOInit(BindPin, OWNER_RX_BIND, 0);
|
|
||||||
IOConfigGPIO(BindPin, IOCFG_OUT_PP);
|
|
||||||
|
|
||||||
// RX line, set high
|
// RX line, set high
|
||||||
IOWrite(BindPin, true);
|
IOWrite(bindIO, true);
|
||||||
|
|
||||||
// Bind window is around 20-140ms after powerup
|
// Bind window is around 20-140ms after powerup
|
||||||
delay(60);
|
delay(60);
|
||||||
LED1_OFF;
|
LED1_OFF;
|
||||||
|
|
||||||
for (i = 0; i < rxConfig->spektrum_sat_bind; i++) {
|
for (int i = 0; i < rxConfig->spektrum_sat_bind; i++) {
|
||||||
|
|
||||||
LED0_OFF;
|
LED0_OFF;
|
||||||
LED2_OFF;
|
LED2_OFF;
|
||||||
// RX line, drive low for 120us
|
// RX line, drive low for 120us
|
||||||
IOWrite(BindPin, false);
|
IOWrite(bindIO, false);
|
||||||
delayMicroseconds(120);
|
delayMicroseconds(120);
|
||||||
|
|
||||||
LED0_ON;
|
LED0_ON;
|
||||||
LED2_ON;
|
LED2_ON;
|
||||||
// RX line, drive high for 120us
|
// RX line, drive high for 120us
|
||||||
IOWrite(BindPin, true);
|
IOWrite(bindIO, true);
|
||||||
delayMicroseconds(120);
|
delayMicroseconds(120);
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
#ifndef BINDPLUG_PIN
|
|
||||||
|
// Release the bind pin to avoid interference with an actual rx pin,
|
||||||
|
// when rxConfig->spektrum_bind_pin_override_ioTag is used.
|
||||||
|
// This happens when the bind pin is connected in parallel to the rx pin.
|
||||||
|
|
||||||
|
if (rxConfig->spektrum_bind_pin_override_ioTag) {
|
||||||
|
delay(50); // Keep it high for 50msec
|
||||||
|
IOConfigGPIO(bindIO, IOCFG_IN_FLOATING);
|
||||||
|
}
|
||||||
|
|
||||||
// If we came here as a result of hard reset (power up, with spektrum_sat_bind set), then reset it back to zero and write config
|
// If we came here as a result of hard reset (power up, with spektrum_sat_bind set), then reset it back to zero and write config
|
||||||
// Don't reset if hardware bind plug is present
|
// Don't reset if hardware bind plug is present
|
||||||
// Reset only when autoreset is enabled
|
// Reset only when autoreset is enabled
|
||||||
if (rxConfig->spektrum_sat_bind_autoreset == 1 && !isMPUSoftReset()) {
|
|
||||||
|
if (!rxConfig->spektrum_bind_plug_ioTag && rxConfig->spektrum_sat_bind_autoreset == 1 && !isMPUSoftReset()) {
|
||||||
rxConfig->spektrum_sat_bind = 0;
|
rxConfig->spektrum_sat_bind = 0;
|
||||||
saveConfigAndNotify();
|
saveConfigAndNotify();
|
||||||
}
|
}
|
||||||
#endif
|
|
||||||
|
|
||||||
}
|
}
|
||||||
#endif // SPEKTRUM_BIND_PIN
|
#endif // USE_SPEKTRUM_BIND
|
||||||
|
|
||||||
bool spektrumInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig)
|
bool spektrumInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig)
|
||||||
{
|
{
|
||||||
|
@ -276,7 +313,7 @@ bool spektrumInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig
|
||||||
switch (rxConfig->serialrx_provider) {
|
switch (rxConfig->serialrx_provider) {
|
||||||
case SERIALRX_SRXL:
|
case SERIALRX_SRXL:
|
||||||
#ifdef TELEMETRY
|
#ifdef TELEMETRY
|
||||||
srxlEnabled = (feature(FEATURE_TELEMETRY) && !portShared && rxConfig->serialrx_provider == SERIALRX_SRXL);
|
srxlEnabled = (feature(FEATURE_TELEMETRY) && !portShared);
|
||||||
#endif
|
#endif
|
||||||
case SERIALRX_SPEKTRUM2048:
|
case SERIALRX_SPEKTRUM2048:
|
||||||
// 11 bit frames
|
// 11 bit frames
|
||||||
|
|
|
@ -96,8 +96,6 @@
|
||||||
//#define CURRENT_METER_ADC_PIN PA5
|
//#define CURRENT_METER_ADC_PIN PA5
|
||||||
#define RSSI_ADC_PIN PB2
|
#define RSSI_ADC_PIN PB2
|
||||||
|
|
||||||
#define SPEKTRUM_BIND_PIN UART2_RX_PIN
|
|
||||||
|
|
||||||
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||||
|
|
||||||
// IO - stm32f303cc in 48pin package
|
// IO - stm32f303cc in 48pin package
|
||||||
|
|
|
@ -88,8 +88,6 @@
|
||||||
#define SERIALRX_UART SERIAL_PORT_USART2
|
#define SERIALRX_UART SERIAL_PORT_USART2
|
||||||
#define RX_CHANNELS_TAER
|
#define RX_CHANNELS_TAER
|
||||||
|
|
||||||
#define SPEKTRUM_BIND_PIN UART3_RX_PIN
|
|
||||||
|
|
||||||
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||||
|
|
||||||
#define TARGET_IO_PORTA 0xffff
|
#define TARGET_IO_PORTA 0xffff
|
||||||
|
|
|
@ -62,8 +62,8 @@
|
||||||
#define RSSI_ADC_PIN PA1
|
#define RSSI_ADC_PIN PA1
|
||||||
#define EXTERNAL1_ADC_PIN PA5
|
#define EXTERNAL1_ADC_PIN PA5
|
||||||
|
|
||||||
#define SPEKTRUM_BIND_PIN PA3
|
#define USE_SPEKTRUM_BIND
|
||||||
|
#define USE_SPEKTRUM_BIND_PLUG
|
||||||
#define BINDPLUG_PIN PB5
|
#define BINDPLUG_PIN PB5
|
||||||
|
|
||||||
#define DEFAULT_FEATURES FEATURE_MOTOR_STOP
|
#define DEFAULT_FEATURES FEATURE_MOTOR_STOP
|
||||||
|
|
|
@ -114,8 +114,6 @@
|
||||||
// LED strip configuration.
|
// LED strip configuration.
|
||||||
#define LED_STRIP
|
#define LED_STRIP
|
||||||
|
|
||||||
#define SPEKTRUM_BIND_PIN UART2_RX_PIN
|
|
||||||
|
|
||||||
#define BINDPLUG_PIN PB12
|
#define BINDPLUG_PIN PB12
|
||||||
|
|
||||||
#define DEFAULT_FEATURES FEATURE_MOTOR_STOP
|
#define DEFAULT_FEATURES FEATURE_MOTOR_STOP
|
||||||
|
|
|
@ -162,8 +162,6 @@
|
||||||
// LED strip configuration.
|
// LED strip configuration.
|
||||||
#define LED_STRIP
|
#define LED_STRIP
|
||||||
|
|
||||||
#define SPEKTRUM_BIND_PIN UART2_RX_PIN
|
|
||||||
|
|
||||||
#define BINDPLUG_PIN PB2
|
#define BINDPLUG_PIN PB2
|
||||||
|
|
||||||
#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
|
#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
|
||||||
|
|
|
@ -171,8 +171,6 @@
|
||||||
// LED strip configuration.
|
// LED strip configuration.
|
||||||
#define LED_STRIP
|
#define LED_STRIP
|
||||||
|
|
||||||
#define SPEKTRUM_BIND_PIN UART2_RX_PIN
|
|
||||||
|
|
||||||
#define BINDPLUG_PIN PB2
|
#define BINDPLUG_PIN PB2
|
||||||
|
|
||||||
#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
|
#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
|
||||||
|
|
|
@ -127,8 +127,6 @@
|
||||||
#define SBUS_TELEMETRY_UART SERIAL_PORT_USART1
|
#define SBUS_TELEMETRY_UART SERIAL_PORT_USART1
|
||||||
#define DEFAULT_FEATURES (FEATURE_TELEMETRY | FEATURE_OSD)
|
#define DEFAULT_FEATURES (FEATURE_TELEMETRY | FEATURE_OSD)
|
||||||
|
|
||||||
#define SPEKTRUM_BIND_PIN UART2_RX_PIN
|
|
||||||
|
|
||||||
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||||
|
|
||||||
// IO - stm32f303cc in 48pin package
|
// IO - stm32f303cc in 48pin package
|
||||||
|
|
|
@ -152,8 +152,6 @@
|
||||||
|
|
||||||
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||||
|
|
||||||
#define SPEKTRUM_BIND_PIN UART3_RX_PIN
|
|
||||||
|
|
||||||
#define TARGET_IO_PORTA 0xffff
|
#define TARGET_IO_PORTA 0xffff
|
||||||
#define TARGET_IO_PORTB 0xffff
|
#define TARGET_IO_PORTB 0xffff
|
||||||
#define TARGET_IO_PORTC 0xffff
|
#define TARGET_IO_PORTC 0xffff
|
||||||
|
|
|
@ -93,8 +93,6 @@
|
||||||
#define VBAT_ADC_PIN PA0
|
#define VBAT_ADC_PIN PA0
|
||||||
#define RSSI_ADC_PIN PB0
|
#define RSSI_ADC_PIN PB0
|
||||||
|
|
||||||
#define SPEKTRUM_BIND_PIN UART3_RX_PIN
|
|
||||||
|
|
||||||
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||||
|
|
||||||
//#define SONAR
|
//#define SONAR
|
||||||
|
|
|
@ -107,7 +107,7 @@
|
||||||
|
|
||||||
#define DEFAULT_RX_FEATURE FEATURE_RX_PPM
|
#define DEFAULT_RX_FEATURE FEATURE_RX_PPM
|
||||||
#define USE_RX_MSP
|
#define USE_RX_MSP
|
||||||
#define SPEKTRUM_BIND_PIN PA3 // UART2, PA3
|
#define USE_SPEKTRUM_BIND
|
||||||
|
|
||||||
#endif //USE_RX_NRF24
|
#endif //USE_RX_NRF24
|
||||||
|
|
||||||
|
|
|
@ -122,8 +122,6 @@
|
||||||
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
|
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
|
||||||
#define DEFAULT_FEATURES ( FEATURE_OSD )
|
#define DEFAULT_FEATURES ( FEATURE_OSD )
|
||||||
#define CURRENT_METER_SCALE_DEFAULT 250
|
#define CURRENT_METER_SCALE_DEFAULT 250
|
||||||
#define SPEKTRUM_BIND_PIN UART6_RX_PIN
|
|
||||||
|
|
||||||
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||||
|
|
||||||
#define TARGET_IO_PORTA (0xffff & ~(BIT(14)|BIT(13)))
|
#define TARGET_IO_PORTA (0xffff & ~(BIT(14)|BIT(13)))
|
||||||
|
|
|
@ -137,7 +137,6 @@
|
||||||
|
|
||||||
// LED strip configuration.
|
// LED strip configuration.
|
||||||
#define LED_STRIP
|
#define LED_STRIP
|
||||||
#define SPEKTRUM_BIND_PIN UART6_RX_PIN
|
|
||||||
#define BINDPLUG_PIN PB2
|
#define BINDPLUG_PIN PB2
|
||||||
#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
|
#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
|
||||||
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
|
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
|
||||||
|
|
|
@ -130,8 +130,6 @@
|
||||||
|
|
||||||
#define DEFAULT_RX_FEATURE FEATURE_RX_PPM
|
#define DEFAULT_RX_FEATURE FEATURE_RX_PPM
|
||||||
|
|
||||||
#define SPEKTRUM_BIND_PIN UART3_RX_PIN
|
|
||||||
|
|
||||||
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||||
|
|
||||||
// !!TODO - check the TARGET_IO_PORTs are correct
|
// !!TODO - check the TARGET_IO_PORTs are correct
|
||||||
|
|
|
@ -146,8 +146,6 @@
|
||||||
|
|
||||||
#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
|
#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
|
||||||
|
|
||||||
#define SPEKTRUM_BIND_PIN UART6_RX_PIN
|
|
||||||
|
|
||||||
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||||
|
|
||||||
#define TARGET_IO_PORTA 0xffff
|
#define TARGET_IO_PORTA 0xffff
|
||||||
|
|
|
@ -103,8 +103,6 @@
|
||||||
|
|
||||||
#define SERIAL_PORT_COUNT 5
|
#define SERIAL_PORT_COUNT 5
|
||||||
//SPECKTRUM BIND
|
//SPECKTRUM BIND
|
||||||
#define SPEKTRUM_BIND_PIN UART3_RX_PIN
|
|
||||||
|
|
||||||
#define CMS
|
#define CMS
|
||||||
#define USE_MSP_DISPLAYPORT
|
#define USE_MSP_DISPLAYPORT
|
||||||
/*---------------------------------*/
|
/*---------------------------------*/
|
||||||
|
|
|
@ -94,12 +94,6 @@
|
||||||
#define SERIALRX_PROVIDER SERIALRX_SBUS
|
#define SERIALRX_PROVIDER SERIALRX_SBUS
|
||||||
#define SERIALRX_UART SERIAL_PORT_USART3
|
#define SERIALRX_UART SERIAL_PORT_USART3
|
||||||
|
|
||||||
#if defined(FF_RADIANCE)
|
|
||||||
#define SPEKTRUM_BIND_PIN UART2_RX_PIN
|
|
||||||
#else
|
|
||||||
#define SPEKTRUM_BIND_PIN UART3_RX_PIN
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#define TRANSPONDER
|
#define TRANSPONDER
|
||||||
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||||
|
|
||||||
|
|
|
@ -98,8 +98,6 @@
|
||||||
#define UART6_TX_PIN PC6
|
#define UART6_TX_PIN PC6
|
||||||
|
|
||||||
#define SERIAL_PORT_COUNT 4
|
#define SERIAL_PORT_COUNT 4
|
||||||
//SPECKTRUM BIND
|
|
||||||
#define SPEKTRUM_BIND_PIN UART3_RX_PIN
|
|
||||||
|
|
||||||
#define CMS
|
#define CMS
|
||||||
#define USE_MSP_DISPLAYPORT
|
#define USE_MSP_DISPLAYPORT
|
||||||
|
|
|
@ -19,6 +19,7 @@
|
||||||
#include <platform.h>
|
#include <platform.h>
|
||||||
|
|
||||||
#ifdef TARGET_CONFIG
|
#ifdef TARGET_CONFIG
|
||||||
|
#include "drivers/io.h"
|
||||||
#include "rx/rx.h"
|
#include "rx/rx.h"
|
||||||
#include "io/serial.h"
|
#include "io/serial.h"
|
||||||
|
|
||||||
|
|
|
@ -138,8 +138,6 @@
|
||||||
#define TELEMETRY_UART SERIAL_PORT_USART3
|
#define TELEMETRY_UART SERIAL_PORT_USART3
|
||||||
#define SERIALRX_UART SERIAL_PORT_USART2
|
#define SERIALRX_UART SERIAL_PORT_USART2
|
||||||
|
|
||||||
#define SPEKTRUM_BIND_PIN UART3_RX_PIN
|
|
||||||
|
|
||||||
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||||
|
|
||||||
#define TARGET_IO_PORTA 0xffff
|
#define TARGET_IO_PORTA 0xffff
|
||||||
|
|
|
@ -19,6 +19,7 @@
|
||||||
#include <platform.h>
|
#include <platform.h>
|
||||||
|
|
||||||
#ifdef TARGET_CONFIG
|
#ifdef TARGET_CONFIG
|
||||||
|
#include "drivers/io.h"
|
||||||
#include "rx/rx.h"
|
#include "rx/rx.h"
|
||||||
#include "io/serial.h"
|
#include "io/serial.h"
|
||||||
|
|
||||||
|
|
|
@ -117,8 +117,6 @@
|
||||||
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
|
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
|
||||||
#define DEFAULT_FEATURES (FEATURE_OSD)
|
#define DEFAULT_FEATURES (FEATURE_OSD)
|
||||||
#define AVOID_UART1_FOR_PWM_PPM
|
#define AVOID_UART1_FOR_PWM_PPM
|
||||||
#define SPEKTRUM_BIND_PIN UART1_RX_PIN
|
|
||||||
|
|
||||||
#define SERIALRX_PROVIDER SERIALRX_SBUS
|
#define SERIALRX_PROVIDER SERIALRX_SBUS
|
||||||
#define TELEMETRY_UART SERIAL_PORT_USART6
|
#define TELEMETRY_UART SERIAL_PORT_USART6
|
||||||
#define SERIALRX_UART SERIAL_PORT_USART1
|
#define SERIALRX_UART SERIAL_PORT_USART1
|
||||||
|
|
|
@ -169,8 +169,6 @@
|
||||||
|
|
||||||
#define DEFAULT_RX_FEATURE FEATURE_RX_PPM
|
#define DEFAULT_RX_FEATURE FEATURE_RX_PPM
|
||||||
|
|
||||||
#define SPEKTRUM_BIND_PIN UART3_RX_PIN
|
|
||||||
|
|
||||||
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||||
|
|
||||||
#define USE_ESC_SENSOR
|
#define USE_ESC_SENSOR
|
||||||
|
|
|
@ -179,8 +179,6 @@
|
||||||
#define SERIALRX_UART SERIAL_PORT_USART1
|
#define SERIALRX_UART SERIAL_PORT_USART1
|
||||||
#define SERIALRX_PROVIDER SERIALRX_SBUS
|
#define SERIALRX_PROVIDER SERIALRX_SBUS
|
||||||
|
|
||||||
#define SPEKTRUM_BIND_PIN UART3_RX_PIN
|
|
||||||
|
|
||||||
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||||
|
|
||||||
#define TARGET_IO_PORTA 0xffff
|
#define TARGET_IO_PORTA 0xffff
|
||||||
|
|
|
@ -138,7 +138,11 @@
|
||||||
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
|
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
|
||||||
#define SERIALRX_PROVIDER SERIALRX_SBUS
|
#define SERIALRX_PROVIDER SERIALRX_SBUS
|
||||||
|
|
||||||
#define SPEKTRUM_BIND_PIN PB11
|
// XXX To target maintainer:
|
||||||
|
// USE_SPEKTRUM_BIND is enabled for this target, and it will use
|
||||||
|
// RX (or TX if half-duplex) pin of the UART the receiver is connected.
|
||||||
|
// If PB11 is critical for this target, please resurrect this line.
|
||||||
|
//#define SPEKTRUM_BIND_PIN PB11
|
||||||
|
|
||||||
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||||
|
|
||||||
|
|
|
@ -91,8 +91,6 @@
|
||||||
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
|
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
|
||||||
#define SERIALRX_UART SERIAL_PORT_USART2
|
#define SERIALRX_UART SERIAL_PORT_USART2
|
||||||
|
|
||||||
#define SPEKTRUM_BIND_PIN UART2_RX_PIN
|
|
||||||
|
|
||||||
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||||
|
|
||||||
// IO - stm32f303cc in 48pin package
|
// IO - stm32f303cc in 48pin package
|
||||||
|
|
|
@ -81,8 +81,6 @@
|
||||||
|
|
||||||
#undef LED_STRIP
|
#undef LED_STRIP
|
||||||
|
|
||||||
#define SPEKTRUM_BIND_PIN UART3_RX_PIN
|
|
||||||
|
|
||||||
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||||
|
|
||||||
/*
|
/*
|
||||||
|
|
|
@ -105,8 +105,6 @@
|
||||||
|
|
||||||
#define DEFAULT_RX_FEATURE FEATURE_RX_PPM
|
#define DEFAULT_RX_FEATURE FEATURE_RX_PPM
|
||||||
|
|
||||||
#define SPEKTRUM_BIND_PIN UART3_RX_PIN
|
|
||||||
|
|
||||||
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||||
|
|
||||||
// IO - stm32f303cc in 48pin package
|
// IO - stm32f303cc in 48pin package
|
||||||
|
|
|
@ -101,8 +101,6 @@
|
||||||
|
|
||||||
#define AVOID_UART2_FOR_PWM_PPM
|
#define AVOID_UART2_FOR_PWM_PPM
|
||||||
|
|
||||||
#define SPEKTRUM_BIND_PIN UART2_RX_PIN
|
|
||||||
|
|
||||||
#define TARGET_IO_PORTA 0xffff
|
#define TARGET_IO_PORTA 0xffff
|
||||||
#define TARGET_IO_PORTB 0xffff
|
#define TARGET_IO_PORTB 0xffff
|
||||||
#define TARGET_IO_PORTC 0xffff
|
#define TARGET_IO_PORTC 0xffff
|
||||||
|
|
|
@ -178,8 +178,6 @@
|
||||||
#define SERIALRX_PROVIDER SERIALRX_SBUS
|
#define SERIALRX_PROVIDER SERIALRX_SBUS
|
||||||
#define SERIALRX_UART SERIAL_PORT_USART1
|
#define SERIALRX_UART SERIAL_PORT_USART1
|
||||||
|
|
||||||
#define SPEKTRUM_BIND_PIN UART3_RX_PIN
|
|
||||||
|
|
||||||
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||||
|
|
||||||
#define TARGET_IO_PORTA 0xffff
|
#define TARGET_IO_PORTA 0xffff
|
||||||
|
|
|
@ -157,8 +157,6 @@
|
||||||
#define DEFAULT_FEATURES (FEATURE_TELEMETRY)
|
#define DEFAULT_FEATURES (FEATURE_TELEMETRY)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#define SPEKTRUM_BIND_PIN UART1_RX_PIN
|
|
||||||
|
|
||||||
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||||
|
|
||||||
#define USE_ESCSERIAL
|
#define USE_ESCSERIAL
|
||||||
|
|
|
@ -70,7 +70,7 @@
|
||||||
#define USE_I2C_DEVICE_2
|
#define USE_I2C_DEVICE_2
|
||||||
#define I2C_DEVICE (I2CDEV_2)
|
#define I2C_DEVICE (I2CDEV_2)
|
||||||
|
|
||||||
#define SPEKTRUM_BIND_PIN PA3
|
#define USE_SPEKTRUM_BIND
|
||||||
|
|
||||||
#define BRUSHED_MOTORS
|
#define BRUSHED_MOTORS
|
||||||
#define DEFAULT_FEATURES FEATURE_MOTOR_STOP
|
#define DEFAULT_FEATURES FEATURE_MOTOR_STOP
|
||||||
|
|
|
@ -98,8 +98,6 @@
|
||||||
|
|
||||||
#define USE_ESC_SENSOR
|
#define USE_ESC_SENSOR
|
||||||
|
|
||||||
#define SPEKTRUM_BIND_PIN UART2_RX_PIN
|
|
||||||
|
|
||||||
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||||
|
|
||||||
// IO - stm32f303cc in 48pin package
|
// IO - stm32f303cc in 48pin package
|
||||||
|
|
|
@ -123,8 +123,6 @@
|
||||||
#define SERIALRX_UART SERIAL_PORT_USART3
|
#define SERIALRX_UART SERIAL_PORT_USART3
|
||||||
#define RX_CHANNELS_TAER
|
#define RX_CHANNELS_TAER
|
||||||
|
|
||||||
#define SPEKTRUM_BIND_PIN UART3_RX_PIN
|
|
||||||
|
|
||||||
#define BINDPLUG_PIN PA13
|
#define BINDPLUG_PIN PA13
|
||||||
|
|
||||||
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||||
|
|
|
@ -146,7 +146,7 @@
|
||||||
#define RSSI_ADC_PIN PA1
|
#define RSSI_ADC_PIN PA1
|
||||||
#define EXTERNAL1_ADC_PIN PA5
|
#define EXTERNAL1_ADC_PIN PA5
|
||||||
|
|
||||||
#define SPEKTRUM_BIND_PIN PA3
|
#define USE_SPEKTRUM_BIND_PIN
|
||||||
|
|
||||||
#define DEFAULT_RX_FEATURE FEATURE_RX_PPM
|
#define DEFAULT_RX_FEATURE FEATURE_RX_PPM
|
||||||
|
|
||||||
|
|
|
@ -128,8 +128,6 @@
|
||||||
|
|
||||||
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||||
|
|
||||||
#define SPEKTRUM_BIND_PIN UART3_RX_PIN
|
|
||||||
|
|
||||||
#define TARGET_IO_PORTA 0xffff
|
#define TARGET_IO_PORTA 0xffff
|
||||||
#define TARGET_IO_PORTB 0xffff
|
#define TARGET_IO_PORTB 0xffff
|
||||||
#define TARGET_IO_PORTC 0xffff
|
#define TARGET_IO_PORTC 0xffff
|
||||||
|
|
|
@ -169,10 +169,6 @@
|
||||||
|
|
||||||
//#define AVOID_UART3_FOR_PWM_PPM // Disable this for using UART3
|
//#define AVOID_UART3_FOR_PWM_PPM // Disable this for using UART3
|
||||||
|
|
||||||
#define SPEKTRUM_BIND_PIN UART3_RX_PIN
|
|
||||||
|
|
||||||
#define BINDPLUG_PIN PB0
|
|
||||||
|
|
||||||
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||||
|
|
||||||
#define TARGET_IO_PORTA 0xffff
|
#define TARGET_IO_PORTA 0xffff
|
||||||
|
|
|
@ -189,8 +189,6 @@
|
||||||
|
|
||||||
#define DEFAULT_FEATURES (FEATURE_OSD)
|
#define DEFAULT_FEATURES (FEATURE_OSD)
|
||||||
#define AVOID_UART1_FOR_PWM_PPM
|
#define AVOID_UART1_FOR_PWM_PPM
|
||||||
#define SPEKTRUM_BIND_PIN UART1_RX_PIN
|
|
||||||
|
|
||||||
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||||
|
|
||||||
#define TARGET_IO_PORTA (0xffff & ~(BIT(14)|BIT(13)))
|
#define TARGET_IO_PORTA (0xffff & ~(BIT(14)|BIT(13)))
|
||||||
|
|
|
@ -109,8 +109,6 @@
|
||||||
#define NAV_GPS_GLITCH_DETECTION
|
#define NAV_GPS_GLITCH_DETECTION
|
||||||
#define NAV_MAX_WAYPOINTS 60
|
#define NAV_MAX_WAYPOINTS 60
|
||||||
|
|
||||||
#define SPEKTRUM_BIND_PIN UART2_RX_PIN
|
|
||||||
|
|
||||||
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||||
|
|
||||||
#define TARGET_IO_PORTA 0xffff
|
#define TARGET_IO_PORTA 0xffff
|
||||||
|
|
|
@ -258,8 +258,6 @@
|
||||||
#define DEFAULT_FEATURES FEATURE_TELEMETRY
|
#define DEFAULT_FEATURES FEATURE_TELEMETRY
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#define SPEKTRUM_BIND_PIN UART3_RX_PIN
|
|
||||||
|
|
||||||
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||||
|
|
||||||
#define TARGET_IO_PORTA 0xffff
|
#define TARGET_IO_PORTA 0xffff
|
||||||
|
|
|
@ -84,8 +84,6 @@
|
||||||
#define VBAT_ADC_PIN PA6
|
#define VBAT_ADC_PIN PA6
|
||||||
#define RSSI_ADC_PIN PA5
|
#define RSSI_ADC_PIN PA5
|
||||||
|
|
||||||
#define SPEKTRUM_BIND_PIN UART2_RX_PIN
|
|
||||||
|
|
||||||
#define TARGET_IO_PORTA 0xffff
|
#define TARGET_IO_PORTA 0xffff
|
||||||
#define TARGET_IO_PORTB 0xffff
|
#define TARGET_IO_PORTB 0xffff
|
||||||
#define TARGET_IO_PORTC 0xffff
|
#define TARGET_IO_PORTC 0xffff
|
||||||
|
|
|
@ -144,8 +144,6 @@
|
||||||
|
|
||||||
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||||
|
|
||||||
#define SPEKTRUM_BIND_PIN UART3_RX_PIN
|
|
||||||
|
|
||||||
// IO - stm32f303rc in 64pin package
|
// IO - stm32f303rc in 64pin package
|
||||||
#define TARGET_IO_PORTA 0xffff
|
#define TARGET_IO_PORTA 0xffff
|
||||||
#define TARGET_IO_PORTB 0xffff
|
#define TARGET_IO_PORTB 0xffff
|
||||||
|
|
|
@ -92,8 +92,6 @@
|
||||||
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
|
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
|
||||||
#define SERIALRX_UART SERIAL_PORT_USART2
|
#define SERIALRX_UART SERIAL_PORT_USART2
|
||||||
|
|
||||||
#define SPEKTRUM_BIND_PIN UART2_RX_PIN
|
|
||||||
|
|
||||||
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||||
|
|
||||||
// IO - stm32f303cc in 48pin package
|
// IO - stm32f303cc in 48pin package
|
||||||
|
|
|
@ -148,8 +148,6 @@
|
||||||
|
|
||||||
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT
|
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT
|
||||||
|
|
||||||
#define SPEKTRUM_BIND_PIN UART3_RX_PIN
|
|
||||||
|
|
||||||
#define DEFAULT_RX_FEATURE FEATURE_RX_PPM
|
#define DEFAULT_RX_FEATURE FEATURE_RX_PPM
|
||||||
#define DEFAULT_FEATURES (FEATURE_RX_SERIAL | FEATURE_OSD)
|
#define DEFAULT_FEATURES (FEATURE_RX_SERIAL | FEATURE_OSD)
|
||||||
|
|
||||||
|
|
|
@ -90,8 +90,6 @@
|
||||||
|
|
||||||
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||||
|
|
||||||
#define SPEKTRUM_BIND_PIN UART2_RX_PIN
|
|
||||||
|
|
||||||
//#define SONAR
|
//#define SONAR
|
||||||
//#define SONAR_ECHO_PIN PB1
|
//#define SONAR_ECHO_PIN PB1
|
||||||
//#define SONAR_TRIGGER_PIN PA2
|
//#define SONAR_TRIGGER_PIN PA2
|
||||||
|
|
|
@ -189,8 +189,6 @@
|
||||||
#define DEFAULT_RX_FEATURE FEATURE_RX_PPM
|
#define DEFAULT_RX_FEATURE FEATURE_RX_PPM
|
||||||
#define DEFAULT_FEATURES (FEATURE_TRANSPONDER | FEATURE_RSSI_ADC | FEATURE_TELEMETRY)
|
#define DEFAULT_FEATURES (FEATURE_TRANSPONDER | FEATURE_RSSI_ADC | FEATURE_TELEMETRY)
|
||||||
|
|
||||||
#define SPEKTRUM_BIND_PIN UART3_RX_PIN
|
|
||||||
|
|
||||||
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||||
|
|
||||||
// IO - stm32f303cc in 48pin package
|
// IO - stm32f303cc in 48pin package
|
||||||
|
|
|
@ -172,8 +172,6 @@
|
||||||
#define DEFAULT_RX_FEATURE FEATURE_RX_PPM
|
#define DEFAULT_RX_FEATURE FEATURE_RX_PPM
|
||||||
#define DEFAULT_FEATURES (FEATURE_TRANSPONDER | FEATURE_RSSI_ADC | FEATURE_TELEMETRY)
|
#define DEFAULT_FEATURES (FEATURE_TRANSPONDER | FEATURE_RSSI_ADC | FEATURE_TELEMETRY)
|
||||||
|
|
||||||
#define SPEKTRUM_BIND_PIN UART3_RX_PIN
|
|
||||||
|
|
||||||
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||||
|
|
||||||
// IO - stm32f303cc in 48pin package
|
// IO - stm32f303cc in 48pin package
|
||||||
|
|
|
@ -186,8 +186,6 @@
|
||||||
#define BINDPLUG_PIN BUTTON_B_PIN
|
#define BINDPLUG_PIN BUTTON_B_PIN
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#define SPEKTRUM_BIND_PIN UART2_RX_PIN
|
|
||||||
|
|
||||||
#define TARGET_IO_PORTA 0xffff
|
#define TARGET_IO_PORTA 0xffff
|
||||||
#define TARGET_IO_PORTB 0xffff
|
#define TARGET_IO_PORTB 0xffff
|
||||||
#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15))
|
#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15))
|
||||||
|
|
|
@ -184,8 +184,6 @@
|
||||||
#define BUTTONS // Physically located on the optional OSD/VTX board.
|
#define BUTTONS // Physically located on the optional OSD/VTX board.
|
||||||
#define BUTTON_A_PIN PD2
|
#define BUTTON_A_PIN PD2
|
||||||
|
|
||||||
#define SPEKTRUM_BIND_PIN UART2_RX_PIN
|
|
||||||
|
|
||||||
// FIXME While it's possible to use the button on the OSD/VTX board for binding enabling it here will break binding unless you have the OSD/VTX connected.
|
// FIXME While it's possible to use the button on the OSD/VTX board for binding enabling it here will break binding unless you have the OSD/VTX connected.
|
||||||
//#define BINDPLUG_PIN BUTTON_A_PIN
|
//#define BINDPLUG_PIN BUTTON_A_PIN
|
||||||
|
|
||||||
|
|
|
@ -176,8 +176,6 @@
|
||||||
#define TELEMETRY_UART SERIAL_PORT_UART5
|
#define TELEMETRY_UART SERIAL_PORT_UART5
|
||||||
#define SERIALRX_PROVIDER SERIALRX_SBUS
|
#define SERIALRX_PROVIDER SERIALRX_SBUS
|
||||||
|
|
||||||
#define SPEKTRUM_BIND_PIN UART2_RX_PIN
|
|
||||||
|
|
||||||
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||||
|
|
||||||
#define TARGET_IO_PORTA 0xffff
|
#define TARGET_IO_PORTA 0xffff
|
||||||
|
|
|
@ -214,8 +214,6 @@
|
||||||
#define BUTTON_A_PIN PB8
|
#define BUTTON_A_PIN PB8
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#define SPEKTRUM_BIND_PIN UART2_RX_PIN
|
|
||||||
|
|
||||||
// FIXME While it's possible to use the button on the OSD/VTX board for binding enabling it here will break binding unless you have the OSD/VTX connected.
|
// FIXME While it's possible to use the button on the OSD/VTX board for binding enabling it here will break binding unless you have the OSD/VTX connected.
|
||||||
//#define BINDPLUG_PIN BUTTON_A_PIN
|
//#define BINDPLUG_PIN BUTTON_A_PIN
|
||||||
|
|
||||||
|
|
|
@ -175,8 +175,6 @@
|
||||||
|
|
||||||
#define USE_ESC_SENSOR
|
#define USE_ESC_SENSOR
|
||||||
|
|
||||||
#define SPEKTRUM_BIND_PIN PA3 // USART2, PA3
|
|
||||||
|
|
||||||
#define SONAR
|
#define SONAR
|
||||||
#define SONAR_TRIGGER_PIN PB0
|
#define SONAR_TRIGGER_PIN PB0
|
||||||
#define SONAR_ECHO_PIN PB1
|
#define SONAR_ECHO_PIN PB1
|
||||||
|
|
|
@ -165,10 +165,6 @@
|
||||||
|
|
||||||
//#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
|
//#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
|
||||||
|
|
||||||
/*
|
|
||||||
#define SPEKTRUM_BIND_PIN PB11
|
|
||||||
*/
|
|
||||||
|
|
||||||
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||||
|
|
||||||
#define TARGET_IO_PORTA 0xffff
|
#define TARGET_IO_PORTA 0xffff
|
||||||
|
|
|
@ -115,8 +115,6 @@
|
||||||
|
|
||||||
#define DEFAULT_RX_FEATURE FEATURE_RX_PPM
|
#define DEFAULT_RX_FEATURE FEATURE_RX_PPM
|
||||||
|
|
||||||
#define SPEKTRUM_BIND_PIN UART3_RX_PIN
|
|
||||||
|
|
||||||
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||||
|
|
||||||
// IO - stm32f303cc in 48pin package
|
// IO - stm32f303cc in 48pin package
|
||||||
|
|
|
@ -122,6 +122,11 @@
|
||||||
#define VTX_CONTROL
|
#define VTX_CONTROL
|
||||||
#define VTX_SMARTAUDIO
|
#define VTX_SMARTAUDIO
|
||||||
#define VTX_TRAMP
|
#define VTX_TRAMP
|
||||||
|
|
||||||
|
#ifdef USE_SERIALRX_SPEKTRUM
|
||||||
|
#define USE_SPEKTRUM_BIND
|
||||||
|
#define USE_SPEKTRUM_BIND_PLUG
|
||||||
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if (FLASH_SIZE > 256)
|
#if (FLASH_SIZE > 256)
|
||||||
|
|
|
@ -39,6 +39,7 @@ extern "C" {
|
||||||
|
|
||||||
#include "io/beeper.h"
|
#include "io/beeper.h"
|
||||||
|
|
||||||
|
#include "drivers/io.h"
|
||||||
#include "rx/rx.h"
|
#include "rx/rx.h"
|
||||||
|
|
||||||
extern boxBitmask_t rcModeActivationMask;
|
extern boxBitmask_t rcModeActivationMask;
|
||||||
|
|
|
@ -31,6 +31,7 @@ extern "C" {
|
||||||
|
|
||||||
#include "sensors/battery.h"
|
#include "sensors/battery.h"
|
||||||
|
|
||||||
|
#include "drivers/io.h"
|
||||||
#include "rx/rx.h"
|
#include "rx/rx.h"
|
||||||
|
|
||||||
#include "fc/config.h"
|
#include "fc/config.h"
|
||||||
|
|
|
@ -23,6 +23,7 @@
|
||||||
extern "C" {
|
extern "C" {
|
||||||
#include "platform.h"
|
#include "platform.h"
|
||||||
|
|
||||||
|
#include "drivers/io.h"
|
||||||
#include "common/maths.h"
|
#include "common/maths.h"
|
||||||
#include "config/parameter_group_ids.h"
|
#include "config/parameter_group_ids.h"
|
||||||
#include "fc/rc_controls.h"
|
#include "fc/rc_controls.h"
|
||||||
|
|
|
@ -23,6 +23,7 @@
|
||||||
extern "C" {
|
extern "C" {
|
||||||
#include "platform.h"
|
#include "platform.h"
|
||||||
|
|
||||||
|
#include "drivers/io.h"
|
||||||
#include "rx/rx.h"
|
#include "rx/rx.h"
|
||||||
#include "fc/rc_modes.h"
|
#include "fc/rc_modes.h"
|
||||||
#include "common/maths.h"
|
#include "common/maths.h"
|
||||||
|
|
Loading…
Reference in New Issue