mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-15 20:35:33 +03:00
Spektrum Satelitte bind code ported from Baseflight
includes support for a hardware bind plug (PB5 pin 41) Activate via OPTIONS="HARDWARE_BIND_PLUG" during make
This commit is contained in:
parent
dd54a59991
commit
c80090f39f
6 changed files with 94 additions and 1 deletions
|
@ -334,6 +334,7 @@ static void resetConf(void)
|
||||||
resetTelemetryConfig(&masterConfig.telemetryConfig);
|
resetTelemetryConfig(&masterConfig.telemetryConfig);
|
||||||
|
|
||||||
masterConfig.rxConfig.serialrx_provider = 0;
|
masterConfig.rxConfig.serialrx_provider = 0;
|
||||||
|
masterConfig.rxConfig.spektrum_sat_bind = 0;
|
||||||
masterConfig.rxConfig.midrc = 1500;
|
masterConfig.rxConfig.midrc = 1500;
|
||||||
masterConfig.rxConfig.mincheck = 1100;
|
masterConfig.rxConfig.mincheck = 1100;
|
||||||
masterConfig.rxConfig.maxcheck = 1900;
|
masterConfig.rxConfig.maxcheck = 1900;
|
||||||
|
|
|
@ -271,6 +271,7 @@ const clivalue_t valueTable[] = {
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
{ "serialrx_provider", VAR_UINT8 | MASTER_VALUE, &masterConfig.rxConfig.serialrx_provider, 0, SERIALRX_PROVIDER_MAX },
|
{ "serialrx_provider", VAR_UINT8 | MASTER_VALUE, &masterConfig.rxConfig.serialrx_provider, 0, SERIALRX_PROVIDER_MAX },
|
||||||
|
{ "spektrum_sat_bind", VAR_UINT8 | MASTER_VALUE, &masterConfig.rxConfig.spektrum_sat_bind, 0, 10 },
|
||||||
|
|
||||||
{ "telemetry_provider", VAR_UINT8 | MASTER_VALUE, &masterConfig.telemetryConfig.telemetry_provider, 0, TELEMETRY_PROVIDER_MAX },
|
{ "telemetry_provider", VAR_UINT8 | MASTER_VALUE, &masterConfig.telemetryConfig.telemetry_provider, 0, TELEMETRY_PROVIDER_MAX },
|
||||||
{ "telemetry_switch", VAR_UINT8 | MASTER_VALUE, &masterConfig.telemetryConfig.telemetry_switch, 0, 1 },
|
{ "telemetry_switch", VAR_UINT8 | MASTER_VALUE, &masterConfig.telemetryConfig.telemetry_switch, 0, 1 },
|
||||||
|
|
|
@ -1013,6 +1013,7 @@ static bool processOutCommand(uint8_t cmdMSP)
|
||||||
case MSP_RX_CONFIG:
|
case MSP_RX_CONFIG:
|
||||||
headSerialReply(7);
|
headSerialReply(7);
|
||||||
serialize8(masterConfig.rxConfig.serialrx_provider);
|
serialize8(masterConfig.rxConfig.serialrx_provider);
|
||||||
|
serialize8(masterConfig.rxConfig.spektrum_sat_bind);
|
||||||
serialize16(masterConfig.rxConfig.maxcheck);
|
serialize16(masterConfig.rxConfig.maxcheck);
|
||||||
serialize16(masterConfig.rxConfig.midrc);
|
serialize16(masterConfig.rxConfig.midrc);
|
||||||
serialize16(masterConfig.rxConfig.mincheck);
|
serialize16(masterConfig.rxConfig.mincheck);
|
||||||
|
@ -1288,6 +1289,7 @@ static bool processInCommand(void)
|
||||||
case MSP_SET_RX_CONFIG:
|
case MSP_SET_RX_CONFIG:
|
||||||
headSerialReply(0);
|
headSerialReply(0);
|
||||||
masterConfig.rxConfig.serialrx_provider = read8();
|
masterConfig.rxConfig.serialrx_provider = read8();
|
||||||
|
masterConfig.rxConfig.spektrum_sat_bind = read8();
|
||||||
masterConfig.rxConfig.maxcheck = read16();
|
masterConfig.rxConfig.maxcheck = read16();
|
||||||
masterConfig.rxConfig.midrc = read16();
|
masterConfig.rxConfig.midrc = read16();
|
||||||
masterConfig.rxConfig.mincheck = read16();
|
masterConfig.rxConfig.mincheck = read16();
|
||||||
|
|
|
@ -105,7 +105,7 @@ void imuInit(void);
|
||||||
void displayInit(rxConfig_t *intialRxConfig);
|
void displayInit(rxConfig_t *intialRxConfig);
|
||||||
void ledStripInit(ledConfig_t *ledConfigsToUse, hsvColor_t *colorsToUse, failsafe_t* failsafeToUse);
|
void ledStripInit(ledConfig_t *ledConfigsToUse, hsvColor_t *colorsToUse, failsafe_t* failsafeToUse);
|
||||||
void loop(void);
|
void loop(void);
|
||||||
|
void spektrumBind(rxConfig_t *rxConfig);
|
||||||
|
|
||||||
#ifdef STM32F303xC
|
#ifdef STM32F303xC
|
||||||
// from system_stm32f30x.c
|
// from system_stm32f30x.c
|
||||||
|
@ -150,6 +150,19 @@ void init(void)
|
||||||
|
|
||||||
systemInit();
|
systemInit();
|
||||||
|
|
||||||
|
// Spektrum sattelite bind - ported from Baseflight
|
||||||
|
if (feature(FEATURE_RX_MSP)) {
|
||||||
|
switch (masterConfig.rxConfig.serialrx_provider) {
|
||||||
|
case SERIALRX_SPEKTRUM1024:
|
||||||
|
case SERIALRX_SPEKTRUM2048:
|
||||||
|
// 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.
|
||||||
|
// The rest of Spektrum initialization will happen later - via spektrumInit()
|
||||||
|
spektrumBind(&masterConfig.rxConfig);
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
delay(100);
|
delay(100);
|
||||||
|
|
||||||
timerInit(); // timer must be initialized before any channel is allocated
|
timerInit(); // timer must be initialized before any channel is allocated
|
||||||
|
|
|
@ -65,6 +65,7 @@ extern int16_t rcData[MAX_SUPPORTED_RC_CHANNEL_COUNT]; // interval [1000;2
|
||||||
typedef struct rxConfig_s {
|
typedef struct rxConfig_s {
|
||||||
uint8_t rcmap[MAX_MAPPABLE_RX_INPUTS]; // mapping of radio channels to internal RPYTA+ order
|
uint8_t rcmap[MAX_MAPPABLE_RX_INPUTS]; // mapping of radio channels to internal RPYTA+ order
|
||||||
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_provider; // type of UART-based receiver (0 = spek 10, 1 = spek 11, 2 = sbus). Must be enabled by FEATURE_RX_SERIAL first.
|
||||||
|
uint8_t spektrum_sat_bind; // number of bind pules for Spektrum sattelite recievers
|
||||||
uint16_t midrc; // Some radios have not a neutral point centered on 1500. can be changed here
|
uint16_t midrc; // Some radios have not a neutral point centered on 1500. can be changed here
|
||||||
uint16_t mincheck; // minimum rc end
|
uint16_t mincheck; // minimum rc end
|
||||||
uint16_t maxcheck; // maximum rc end
|
uint16_t maxcheck; // maximum rc end
|
||||||
|
|
|
@ -21,12 +21,15 @@
|
||||||
|
|
||||||
#include "platform.h"
|
#include "platform.h"
|
||||||
|
|
||||||
|
#include "drivers/gpio.h"
|
||||||
#include "drivers/system.h"
|
#include "drivers/system.h"
|
||||||
|
|
||||||
#include "drivers/serial.h"
|
#include "drivers/serial.h"
|
||||||
#include "drivers/serial_uart.h"
|
#include "drivers/serial_uart.h"
|
||||||
#include "io/serial.h"
|
#include "io/serial.h"
|
||||||
|
|
||||||
|
#include "config/config.h"
|
||||||
|
|
||||||
#include "rx/rx.h"
|
#include "rx/rx.h"
|
||||||
#include "rx/spektrum.h"
|
#include "rx/spektrum.h"
|
||||||
|
|
||||||
|
@ -40,6 +43,8 @@
|
||||||
|
|
||||||
#define SPEKTRUM_BAUDRATE 115200
|
#define SPEKTRUM_BAUDRATE 115200
|
||||||
|
|
||||||
|
#define BKP_SOFTRESET (0x50F7B007)
|
||||||
|
|
||||||
static uint8_t spek_chan_shift;
|
static uint8_t spek_chan_shift;
|
||||||
static uint8_t spek_chan_mask;
|
static uint8_t spek_chan_mask;
|
||||||
static bool rcFrameComplete = false;
|
static bool rcFrameComplete = false;
|
||||||
|
@ -138,3 +143,73 @@ static uint16_t spektrumReadRawRC(rxRuntimeConfig_t *rxRuntimeConfig, uint8_t ch
|
||||||
|
|
||||||
return data;
|
return data;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
uint32_t rccReadBkpDr(void)
|
||||||
|
{
|
||||||
|
return *((uint16_t *)BKP_BASE + 0x04) | *((uint16_t *)BKP_BASE + 0x08) << 16;
|
||||||
|
}
|
||||||
|
|
||||||
|
/* 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.
|
||||||
|
* Known parameters. Tested with DSMX satellite and DX8 radio. Framerate (11ms or 22ms) must be selected from TX.
|
||||||
|
* 9 = DSMX 11ms / DSMX 22ms
|
||||||
|
* 5 = DSM2 11ms 2048 / DSM2 22ms 1024
|
||||||
|
*/
|
||||||
|
void spektrumBind(rxConfig_t *rxConfig)
|
||||||
|
{
|
||||||
|
int i;
|
||||||
|
gpio_config_t gpio;
|
||||||
|
GPIO_TypeDef *spekBindPort;
|
||||||
|
uint16_t spekBindPin;
|
||||||
|
|
||||||
|
#ifdef HARDWARE_BIND_PLUG
|
||||||
|
// Check status of bind plug and exit if not active
|
||||||
|
GPIO_TypeDef *hwBindPort;
|
||||||
|
uint16_t hwBindPin;
|
||||||
|
|
||||||
|
hwBindPort = GPIOB;
|
||||||
|
hwBindPin = Pin_5;
|
||||||
|
gpio.speed = Speed_2MHz;
|
||||||
|
gpio.pin = hwBindPin;
|
||||||
|
gpio.mode = Mode_IPU;
|
||||||
|
gpioInit(hwBindPort, &gpio);
|
||||||
|
if (digitalIn(hwBindPort, hwBindPin))
|
||||||
|
return;
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// USART2, PA3
|
||||||
|
spekBindPort = GPIOA;
|
||||||
|
spekBindPin = Pin_3;
|
||||||
|
|
||||||
|
// don't try to bind if: here after soft reset or bind flag is out of range
|
||||||
|
if (rccReadBkpDr() == BKP_SOFTRESET || rxConfig->spektrum_sat_bind == 0 || rxConfig->spektrum_sat_bind > 10)
|
||||||
|
return;
|
||||||
|
|
||||||
|
gpio.speed = Speed_2MHz;
|
||||||
|
gpio.pin = spekBindPin;
|
||||||
|
gpio.mode = Mode_Out_OD;
|
||||||
|
gpioInit(spekBindPort, &gpio);
|
||||||
|
// RX line, set high
|
||||||
|
digitalHi(spekBindPort, spekBindPin);
|
||||||
|
// Bind window is around 20-140ms after powerup
|
||||||
|
delay(60);
|
||||||
|
|
||||||
|
for (i = 0; i < rxConfig->spektrum_sat_bind; i++) {
|
||||||
|
// RX line, drive low for 120us
|
||||||
|
digitalLo(spekBindPort, spekBindPin);
|
||||||
|
delayMicroseconds(120);
|
||||||
|
// RX line, drive high for 120us
|
||||||
|
digitalHi(spekBindPort, spekBindPin);
|
||||||
|
delayMicroseconds(120);
|
||||||
|
}
|
||||||
|
|
||||||
|
#ifndef HARDWARE_BIND_PLUG
|
||||||
|
// If we came here as a result of hard reset (power up, with mcfg.spektrum_sat_bind set), then reset it back to zero and write config
|
||||||
|
// Don't reset if hardware bind plug is present
|
||||||
|
if (rccReadBkpDr() != BKP_SOFTRESET) {
|
||||||
|
rxConfig->spektrum_sat_bind = 0;
|
||||||
|
writeEEPROM(1, true);
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
}
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue