mirror of
https://github.com/iNavFlight/inav.git
synced 2025-07-25 01:05:21 +03:00
Drop SPI RX as not used by any supported hardware
This commit is contained in:
parent
7abe07e9b4
commit
1fec9d7304
19 changed files with 8 additions and 1464 deletions
|
@ -76,7 +76,6 @@ After restoring it's always a good idea to `dump` or `diff` the settings once ag
|
|||
| `dfu` | DFU mode on reboot |
|
||||
| `diff` | List configuration changes from default |
|
||||
| `dump` | Dump configuration |
|
||||
| `eleres_bind` | |
|
||||
| `exit` | |
|
||||
| `feature` | List or enable <val> or disable <-val> |
|
||||
| `flash_erase` | Erase flash chip |
|
||||
|
|
100
docs/Settings.md
100
docs/Settings.md
|
@ -792,76 +792,6 @@ Q factor for dynamic notches
|
|||
|
||||
---
|
||||
|
||||
### eleres_freq
|
||||
|
||||
_// TODO_
|
||||
|
||||
| Default | Min | Max |
|
||||
| --- | --- | --- |
|
||||
| 435 | 415 | 450 |
|
||||
|
||||
---
|
||||
|
||||
### eleres_loc_delay
|
||||
|
||||
_// TODO_
|
||||
|
||||
| Default | Min | Max |
|
||||
| --- | --- | --- |
|
||||
| 240 | 30 | 1800 |
|
||||
|
||||
---
|
||||
|
||||
### eleres_loc_en
|
||||
|
||||
_// TODO_
|
||||
|
||||
| Default | Min | Max |
|
||||
| --- | --- | --- |
|
||||
| OFF | OFF | ON |
|
||||
|
||||
---
|
||||
|
||||
### eleres_loc_power
|
||||
|
||||
_// TODO_
|
||||
|
||||
| Default | Min | Max |
|
||||
| --- | --- | --- |
|
||||
| 7 | 0 | 7 |
|
||||
|
||||
---
|
||||
|
||||
### eleres_signature
|
||||
|
||||
_// TODO_
|
||||
|
||||
| Default | Min | Max |
|
||||
| --- | --- | --- |
|
||||
| 0 | | 4294967295 |
|
||||
|
||||
---
|
||||
|
||||
### eleres_telemetry_en
|
||||
|
||||
_// TODO_
|
||||
|
||||
| Default | Min | Max |
|
||||
| --- | --- | --- |
|
||||
| OFF | OFF | ON |
|
||||
|
||||
---
|
||||
|
||||
### eleres_telemetry_power
|
||||
|
||||
_// TODO_
|
||||
|
||||
| Default | Min | Max |
|
||||
| --- | --- | --- |
|
||||
| 7 | 0 | 7 |
|
||||
|
||||
---
|
||||
|
||||
### esc_sensor_listen_only
|
||||
|
||||
Enable when BLHeli32 Auto Telemetry function is used. Disable in every other case
|
||||
|
@ -5282,36 +5212,6 @@ Defines the shortest pulse width value used when ensuring the channel value is v
|
|||
|
||||
---
|
||||
|
||||
### rx_spi_id
|
||||
|
||||
_// TODO_
|
||||
|
||||
| Default | Min | Max |
|
||||
| --- | --- | --- |
|
||||
| 0 | 0 | 0 |
|
||||
|
||||
---
|
||||
|
||||
### rx_spi_protocol
|
||||
|
||||
_// TODO_
|
||||
|
||||
| Default | Min | Max |
|
||||
| --- | --- | --- |
|
||||
| _target default_ | | |
|
||||
|
||||
---
|
||||
|
||||
### rx_spi_rf_channel_count
|
||||
|
||||
_// TODO_
|
||||
|
||||
| Default | Min | Max |
|
||||
| --- | --- | --- |
|
||||
| 0 | 0 | 8 |
|
||||
|
||||
---
|
||||
|
||||
### safehome_max_distance
|
||||
|
||||
In order for a safehome to be used, it must be less than this distance (in cm) from the arming point.
|
||||
|
|
|
@ -240,8 +240,6 @@ main_sources(COMMON_SRC
|
|||
drivers/resource.h
|
||||
drivers/rcc.c
|
||||
drivers/rcc.h
|
||||
drivers/rx_spi.c
|
||||
drivers/rx_spi.h
|
||||
drivers/serial.c
|
||||
drivers/serial.h
|
||||
drivers/sound_beeper.c
|
||||
|
@ -381,8 +379,6 @@ main_sources(COMMON_SRC
|
|||
|
||||
rx/crsf.c
|
||||
rx/crsf.h
|
||||
rx/eleres.c
|
||||
rx/eleres.h
|
||||
rx/fport.c
|
||||
rx/fport.h
|
||||
rx/fport2.c
|
||||
|
@ -404,8 +400,6 @@ main_sources(COMMON_SRC
|
|||
rx/frsky_crc.h
|
||||
rx/rx.c
|
||||
rx/rx.h
|
||||
rx/rx_spi.c
|
||||
rx/rx_spi.h
|
||||
rx/sbus.c
|
||||
rx/sbus.h
|
||||
rx/sbus_channels.c
|
||||
|
|
|
@ -74,7 +74,7 @@
|
|||
#define PG_SERVO_CONFIG 52
|
||||
//#define PG_IBUS_TELEMETRY_CONFIG 53
|
||||
#define PG_VTX_CONFIG 54
|
||||
#define PG_ELERES_CONFIG 55
|
||||
// #define PG_ELERES_CONFIG 55
|
||||
#define PG_TEMP_SENSOR_CONFIG 56
|
||||
#define PG_CF_END 56
|
||||
|
||||
|
|
|
@ -18,10 +18,10 @@
|
|||
#include "drivers/resource.h"
|
||||
|
||||
const char * const ownerNames[OWNER_TOTAL_COUNT] = {
|
||||
"FREE", "PWM/IO", "PWM", "PPM", "MOTOR", "SERVO", "SOFTSERIAL", "ADC", "SERIAL", "DEBUG", "TIMER",
|
||||
"FREE", "PWM/IO", "MOTOR", "SERVO", "SOFTSERIAL", "ADC", "SERIAL", "TIMER",
|
||||
"RANGEFINDER", "SYSTEM", "SPI", "I2C", "SDCARD", "FLASH", "USB", "BEEPER", "OSD",
|
||||
"BARO", "MPU", "INVERTER", "LED STRIP", "LED", "RECEIVER", "TRANSMITTER",
|
||||
"NRF24", "VTX", "SPI_PREINIT", "COMPASS", "TEMPERATURE", "1-WIRE", "AIRSPEED", "OLED DISPLAY",
|
||||
"VTX", "SPI_PREINIT", "COMPASS", "TEMPERATURE", "1-WIRE", "AIRSPEED", "OLED DISPLAY",
|
||||
"PINIO", "IRLOCK"
|
||||
};
|
||||
|
||||
|
|
|
@ -22,14 +22,11 @@
|
|||
typedef enum {
|
||||
OWNER_FREE = 0,
|
||||
OWNER_PWMIO,
|
||||
OWNER_PWMINPUT,
|
||||
OWNER_PPMINPUT,
|
||||
OWNER_MOTOR,
|
||||
OWNER_SERVO,
|
||||
OWNER_SOFTSERIAL,
|
||||
OWNER_ADC,
|
||||
OWNER_SERIAL,
|
||||
OWNER_PINDEBUG,
|
||||
OWNER_TIMER,
|
||||
OWNER_RANGEFINDER,
|
||||
OWNER_SYSTEM,
|
||||
|
@ -47,7 +44,6 @@ typedef enum {
|
|||
OWNER_LED,
|
||||
OWNER_RX,
|
||||
OWNER_TX,
|
||||
OWNER_RX_SPI,
|
||||
OWNER_VTX,
|
||||
OWNER_SPI_PREINIT,
|
||||
OWNER_COMPASS,
|
||||
|
|
|
@ -1,149 +0,0 @@
|
|||
/*
|
||||
* This file is part of Cleanflight.
|
||||
*
|
||||
* Cleanflight is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* Cleanflight is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
// This file is copied with modifications from project Deviation,
|
||||
// see http://deviationtx.com
|
||||
|
||||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
#include <stdlib.h>
|
||||
|
||||
#include <platform.h>
|
||||
|
||||
#ifdef USE_RX_SPI
|
||||
|
||||
#include "build/build_config.h"
|
||||
|
||||
#include "drivers/time.h"
|
||||
#include "drivers/io.h"
|
||||
#include "io_impl.h"
|
||||
#include "rcc.h"
|
||||
#include "rx_spi.h"
|
||||
|
||||
#include "drivers/bus_spi.h"
|
||||
|
||||
#define DISABLE_RX() {IOHi(IOGetByTag(IO_TAG(RX_NSS_PIN)));}
|
||||
#define ENABLE_RX() {IOLo(IOGetByTag(IO_TAG(RX_NSS_PIN)));}
|
||||
#ifdef RX_CE_PIN
|
||||
#define RX_CE_HI() {IOHi(IOGetByTag(IO_TAG(RX_CE_PIN)));}
|
||||
#define RX_CE_LO() {IOLo(IOGetByTag(IO_TAG(RX_CE_PIN)));}
|
||||
#endif
|
||||
|
||||
|
||||
#ifdef RX_IRQ_PIN
|
||||
static IO_t rxIrqPin = IO_NONE;
|
||||
#endif
|
||||
|
||||
void rxSpiDeviceInit()
|
||||
{
|
||||
static bool hardwareInitialised = false;
|
||||
|
||||
if (hardwareInitialised) {
|
||||
return;
|
||||
}
|
||||
|
||||
const SPIDevice rxSPIDevice = spiDeviceByInstance(RX_SPI_INSTANCE);
|
||||
IOInit(IOGetByTag(IO_TAG(RX_NSS_PIN)), OWNER_SPI, RESOURCE_SPI_CS, rxSPIDevice + 1);
|
||||
|
||||
#ifdef RX_IRQ_PIN
|
||||
rxIrqPin = IOGetByTag(IO_TAG(RX_IRQ_PIN));
|
||||
IOInit(rxIrqPin, OWNER_RX, RESOURCE_NONE, 0);
|
||||
IOConfigGPIO(rxIrqPin, IOCFG_IN_FLOATING);
|
||||
#endif
|
||||
|
||||
#ifdef RX_CE_PIN
|
||||
// CE as OUTPUT
|
||||
IOInit(IOGetByTag(IO_TAG(RX_CE_PIN)), OWNER_RX_SPI, RESOURCE_RX_CE, rxSPIDevice + 1);
|
||||
#if defined(STM32F4)
|
||||
IOConfigGPIOAF(IOGetByTag(IO_TAG(RX_CE_PIN)), SPI_IO_CS_CFG, 0);
|
||||
#endif
|
||||
RX_CE_LO();
|
||||
#endif // RX_CE_PIN
|
||||
DISABLE_RX();
|
||||
|
||||
#ifdef RX_SPI_INSTANCE
|
||||
spiSetSpeed(RX_SPI_INSTANCE, SPI_CLOCK_STANDARD);
|
||||
#endif
|
||||
hardwareInitialised = true;
|
||||
}
|
||||
|
||||
uint8_t rxSpiTransferByte(uint8_t data)
|
||||
{
|
||||
#ifdef RX_SPI_INSTANCE
|
||||
return spiTransferByte(RX_SPI_INSTANCE, data);
|
||||
#else
|
||||
return 0;
|
||||
#endif
|
||||
}
|
||||
|
||||
uint8_t rxSpiWriteByte(uint8_t data)
|
||||
{
|
||||
ENABLE_RX();
|
||||
const uint8_t ret = rxSpiTransferByte(data);
|
||||
DISABLE_RX();
|
||||
return ret;
|
||||
}
|
||||
|
||||
uint8_t rxSpiWriteCommand(uint8_t command, uint8_t data)
|
||||
{
|
||||
ENABLE_RX();
|
||||
const uint8_t ret = rxSpiTransferByte(command);
|
||||
rxSpiTransferByte(data);
|
||||
DISABLE_RX();
|
||||
return ret;
|
||||
}
|
||||
|
||||
uint8_t rxSpiWriteCommandMulti(uint8_t command, const uint8_t *data, uint8_t length)
|
||||
{
|
||||
ENABLE_RX();
|
||||
const uint8_t ret = rxSpiTransferByte(command);
|
||||
for (uint8_t i = 0; i < length; i++) {
|
||||
rxSpiTransferByte(data[i]);
|
||||
}
|
||||
DISABLE_RX();
|
||||
return ret;
|
||||
}
|
||||
|
||||
uint8_t rxSpiReadCommand(uint8_t command, uint8_t data)
|
||||
{
|
||||
ENABLE_RX();
|
||||
rxSpiTransferByte(command);
|
||||
const uint8_t ret = rxSpiTransferByte(data);
|
||||
DISABLE_RX();
|
||||
return ret;
|
||||
}
|
||||
|
||||
uint8_t rxSpiReadCommandMulti(uint8_t command, uint8_t commandData, uint8_t *retData, uint8_t length)
|
||||
{
|
||||
ENABLE_RX();
|
||||
const uint8_t ret = rxSpiTransferByte(command);
|
||||
for (uint8_t i = 0; i < length; i++) {
|
||||
retData[i] = rxSpiTransferByte(commandData);
|
||||
}
|
||||
DISABLE_RX();
|
||||
return ret;
|
||||
}
|
||||
|
||||
#ifdef RX_IRQ_PIN
|
||||
bool rxSpiCheckIrq(void)
|
||||
{
|
||||
return !IORead(rxIrqPin);
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif
|
||||
|
|
@ -1,31 +0,0 @@
|
|||
/*
|
||||
* This file is part of Cleanflight.
|
||||
*
|
||||
* Cleanflight is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* Cleanflight is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
#define RX_SPI_MAX_PAYLOAD_SIZE 32
|
||||
|
||||
void rxSpiDeviceInit(void);
|
||||
uint8_t rxSpiTransferByte(uint8_t data);
|
||||
uint8_t rxSpiWriteByte(uint8_t data);
|
||||
uint8_t rxSpiWriteCommand(uint8_t command, uint8_t data);
|
||||
uint8_t rxSpiWriteCommandMulti(uint8_t command, const uint8_t *data, uint8_t length);
|
||||
uint8_t rxSpiReadCommand(uint8_t command, uint8_t commandData);
|
||||
uint8_t rxSpiReadCommandMulti(uint8_t command, uint8_t commandData, uint8_t *retData, uint8_t length);
|
||||
bool rxSpiCheckIrq(void);
|
||||
|
|
@ -101,7 +101,6 @@ bool cliMode = false;
|
|||
|
||||
#include "rx/rx.h"
|
||||
#include "rx/spektrum.h"
|
||||
#include "rx/eleres.h"
|
||||
#include "rx/srxl2.h"
|
||||
|
||||
#include "scheduler/scheduler.h"
|
||||
|
@ -2852,27 +2851,7 @@ static void cliDfu(char *cmdline)
|
|||
cliRebootEx(true);
|
||||
}
|
||||
|
||||
#ifdef USE_RX_ELERES
|
||||
static void cliEleresBind(char *cmdline)
|
||||
{
|
||||
UNUSED(cmdline);
|
||||
|
||||
if (!(rxConfig()->receiverType == RX_TYPE_SPI && rxConfig()->rx_spi_protocol == RFM22_ELERES)) {
|
||||
cliPrintLine("Eleres not active. Please enable feature ELERES and restart IMU");
|
||||
return;
|
||||
}
|
||||
|
||||
cliPrintLine("Waiting for correct bind signature....");
|
||||
bufWriterFlush(cliWriter);
|
||||
if (eleresBind()) {
|
||||
cliPrintLine("Bind timeout!");
|
||||
} else {
|
||||
cliPrintLine("Bind OK!\r\nPlease restart your transmitter.");
|
||||
}
|
||||
}
|
||||
#endif // USE_RX_ELERES
|
||||
|
||||
#if defined(USE_RX_SPI) || defined (USE_SERIALRX_SRXL2)
|
||||
#if defined (USE_SERIALRX_SRXL2)
|
||||
void cliRxBind(char *cmdline){
|
||||
UNUSED(cmdline);
|
||||
if (rxConfig()->receiverType == RX_TYPE_SERIAL) {
|
||||
|
@ -2888,16 +2867,6 @@ void cliRxBind(char *cmdline){
|
|||
#endif
|
||||
}
|
||||
}
|
||||
#if defined(USE_RX_SPI)
|
||||
else if (rxConfig()->receiverType == RX_TYPE_SPI) {
|
||||
switch (rxConfig()->rx_spi_protocol) {
|
||||
default:
|
||||
cliPrint("Not supported.");
|
||||
break;
|
||||
}
|
||||
|
||||
}
|
||||
#endif
|
||||
}
|
||||
#endif
|
||||
|
||||
|
@ -3873,7 +3842,7 @@ const clicmd_t cmdTable[] = {
|
|||
CLI_COMMAND_DEF("beeper", "turn on/off beeper", "list\r\n"
|
||||
"\t<+|->[name]", cliBeeper),
|
||||
#endif
|
||||
#if defined(USE_RX_SPI) || defined (USE_SERIALRX_SRXL2)
|
||||
#if defined (USE_SERIALRX_SRXL2)
|
||||
CLI_COMMAND_DEF("bind_rx", "initiate binding for RX SPI or SRXL2", NULL, cliRxBind),
|
||||
#endif
|
||||
#if defined(USE_BOOTLOG)
|
||||
|
|
|
@ -37,7 +37,6 @@
|
|||
#include "config/parameter_group_ids.h"
|
||||
|
||||
#include "drivers/system.h"
|
||||
#include "drivers/rx_spi.h"
|
||||
#include "drivers/pwm_mapping.h"
|
||||
#include "drivers/pwm_output.h"
|
||||
#include "drivers/serial.h"
|
||||
|
@ -59,7 +58,6 @@
|
|||
#include "io/osd.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
#include "rx/rx_spi.h"
|
||||
|
||||
#include "flight/mixer.h"
|
||||
#include "flight/servos.h"
|
||||
|
@ -81,9 +79,6 @@
|
|||
#ifndef DEFAULT_FEATURES
|
||||
#define DEFAULT_FEATURES 0
|
||||
#endif
|
||||
#ifndef RX_SPI_DEFAULT_PROTOCOL
|
||||
#define RX_SPI_DEFAULT_PROTOCOL 0
|
||||
#endif
|
||||
|
||||
#define BRUSHED_MOTORS_PWM_RATE 16000
|
||||
#define BRUSHLESS_MOTORS_PWM_RATE 400
|
||||
|
|
|
@ -1005,15 +1005,9 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF
|
|||
sbufWriteU8(dst, 0); // for compatibility with betaflight (rcInterpolation)
|
||||
sbufWriteU8(dst, 0); // for compatibility with betaflight (rcInterpolationInterval)
|
||||
sbufWriteU16(dst, 0); // for compatibility with betaflight (airModeActivateThreshold)
|
||||
#ifdef USE_RX_SPI
|
||||
sbufWriteU8(dst, rxConfig()->rx_spi_protocol);
|
||||
sbufWriteU32(dst, rxConfig()->rx_spi_id);
|
||||
sbufWriteU8(dst, rxConfig()->rx_spi_rf_channel_count);
|
||||
#else
|
||||
sbufWriteU8(dst, 0);
|
||||
sbufWriteU32(dst, 0);
|
||||
sbufWriteU8(dst, 0);
|
||||
#endif
|
||||
sbufWriteU8(dst, 0); // for compatibility with betaflight (fpvCamAngleDegrees)
|
||||
sbufWriteU8(dst, rxConfig()->receiverType);
|
||||
break;
|
||||
|
@ -2592,15 +2586,9 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src)
|
|||
sbufReadU8(src); // for compatibility with betaflight (rcInterpolation)
|
||||
sbufReadU8(src); // for compatibility with betaflight (rcInterpolationInterval)
|
||||
sbufReadU16(src); // for compatibility with betaflight (airModeActivateThreshold)
|
||||
#ifdef USE_RX_SPI
|
||||
rxConfigMutable()->rx_spi_protocol = sbufReadU8(src);
|
||||
rxConfigMutable()->rx_spi_id = sbufReadU32(src);
|
||||
rxConfigMutable()->rx_spi_rf_channel_count = sbufReadU8(src);
|
||||
#else
|
||||
sbufReadU8(src);
|
||||
sbufReadU32(src);
|
||||
sbufReadU8(src);
|
||||
#endif
|
||||
sbufReadU8(src); // for compatibility with betaflight (fpvCamAngleDegrees)
|
||||
rxConfigMutable()->receiverType = sbufReadU8(src); // Won't be modified if buffer is not large enough
|
||||
} else
|
||||
|
|
|
@ -72,8 +72,6 @@
|
|||
#include "msp/msp_serial.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
#include "rx/eleres.h"
|
||||
#include "rx/rx_spi.h"
|
||||
|
||||
#include "scheduler/scheduler.h"
|
||||
|
||||
|
|
|
@ -25,13 +25,10 @@ tables:
|
|||
values: ["NONE", "AUTO", "MS4525", "ADC", "VIRTUAL", "FAKE", "MSP"]
|
||||
enum: pitotSensor_e
|
||||
- name: receiver_type
|
||||
values: ["NONE", "SERIAL", "MSP", "SPI"]
|
||||
values: ["NONE", "SERIAL", "MSP"]
|
||||
enum: rxReceiverType_e
|
||||
- name: serial_rx
|
||||
values: ["SPEK1024", "SPEK2048", "SBUS", "SUMD", "SUMH", "XB-B", "XB-B-RJ01", "IBUS", "JETIEXBUS", "CRSF", "FPORT", "SBUS_FAST", "FPORT2", "SRXL2", "GHST", "MAVLINK"]
|
||||
- name: rx_spi_protocol
|
||||
values: ["ELERES"]
|
||||
enum: rx_spi_protocol_e
|
||||
- name: blackbox_device
|
||||
values: ["SERIAL", "SPIFLASH", "SDCARD"]
|
||||
- name: motor_pwm_protocol
|
||||
|
@ -748,20 +745,6 @@ groups:
|
|||
default_value: OFF
|
||||
condition: USE_SERIAL_RX
|
||||
type: bool
|
||||
- name: rx_spi_protocol
|
||||
condition: USE_RX_SPI
|
||||
table: rx_spi_protocol
|
||||
default_value: :target
|
||||
- name: rx_spi_id
|
||||
condition: USE_RX_SPI
|
||||
min: 0
|
||||
max: 0
|
||||
default_value: :zero
|
||||
- name: rx_spi_rf_channel_count
|
||||
condition: USE_RX_SPI
|
||||
min: 0
|
||||
max: 8
|
||||
default_value: :zero
|
||||
- name: spektrum_sat_bind
|
||||
description: "0 = disabled. Used to bind the spektrum satellite to RX"
|
||||
condition: USE_SPEKTRUM_BIND
|
||||
|
@ -3037,43 +3020,6 @@ groups:
|
|||
min: 1
|
||||
max: 2
|
||||
default_value: 2
|
||||
- name: PG_ELERES_CONFIG
|
||||
type: eleresConfig_t
|
||||
headers: ["rx/eleres.h"]
|
||||
condition: USE_RX_ELERES
|
||||
members:
|
||||
- name: eleres_freq
|
||||
field: eleresFreq
|
||||
min: 415
|
||||
max: 450
|
||||
default_value: 435
|
||||
- name: eleres_telemetry_en
|
||||
field: eleresTelemetryEn
|
||||
type: bool
|
||||
default_value: OFF
|
||||
- name: eleres_telemetry_power
|
||||
field: eleresTelemetryPower
|
||||
min: 0
|
||||
max: 7
|
||||
default_value: 7
|
||||
- name: eleres_loc_en
|
||||
field: eleresLocEn
|
||||
type: bool
|
||||
default_value: OFF
|
||||
- name: eleres_loc_power
|
||||
field: eleresLocPower
|
||||
min: 0
|
||||
max: 7
|
||||
default_value: 7
|
||||
- name: eleres_loc_delay
|
||||
field: eleresLocDelay
|
||||
min: 30
|
||||
max: 1800
|
||||
default_value: 240
|
||||
- name: eleres_signature
|
||||
field: eleresSignature
|
||||
max: UINT32_MAX
|
||||
default_value: :zero
|
||||
|
||||
- name: PG_LED_STRIP_CONFIG
|
||||
type: ledStripConfig_t
|
||||
|
|
|
@ -1,826 +0,0 @@
|
|||
/*
|
||||
This file is part of eLeReS (by Michal Maciakowski - Cyberdrones.com).
|
||||
Adapted for MultiWii by Mis (Romuald Bialy)
|
||||
Ported to STM by Marbalon (Marcin Baliniak)
|
||||
*/
|
||||
|
||||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
#include <stdlib.h>
|
||||
|
||||
#include <string.h>
|
||||
#include "platform.h"
|
||||
|
||||
#include "build/build_config.h"
|
||||
#include "build/debug.h"
|
||||
#include "build/version.h"
|
||||
|
||||
#include "common/axis.h"
|
||||
#include "common/utils.h"
|
||||
|
||||
#include "config/config_master.h"
|
||||
#include "config/parameter_group.h"
|
||||
#include "config/parameter_group_ids.h"
|
||||
|
||||
#include "drivers/sensor.h"
|
||||
#include "drivers/time.h"
|
||||
#include "drivers/io.h"
|
||||
#include "drivers/rx_spi.h"
|
||||
|
||||
#include "fc/runtime_config.h"
|
||||
#include "fc/rc_controls.h"
|
||||
#include "fc/cli.h"
|
||||
#include "flight/imu.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
#include "rx/rx_spi.h"
|
||||
#include "rx/eleres.h"
|
||||
#include "navigation/navigation.h"
|
||||
|
||||
#include "sensors/battery.h"
|
||||
#include "sensors/sensors.h"
|
||||
#include "sensors/barometer.h"
|
||||
#include "sensors/temperature.h"
|
||||
#include "scheduler/scheduler.h"
|
||||
|
||||
#ifdef USE_RX_ELERES
|
||||
|
||||
/***************** eLeReS compatibile reciver on RFM22B module ********************/
|
||||
|
||||
#define RED_LED_ON {if (!redLed) {rfmSpiWrite(0x0e, 0x04);redLed=1;}}
|
||||
#define RED_LED_OFF {if (redLed) {rfmSpiWrite(0x0e, 0x00);redLed=0;}}
|
||||
|
||||
#define RC_CHANS 12
|
||||
#define TRANSMIT 1
|
||||
#define TRANSMITTED 2
|
||||
#define RECEIVE 4
|
||||
#define RECEIVED 8
|
||||
#define PREAMBLE 16
|
||||
|
||||
#define DATA_FLAG 1
|
||||
#define LOCALIZER_FLAG 2
|
||||
#define RELAY_FLAG 4
|
||||
|
||||
#define RF22B_RX_PACKET_RECEIVED_INTERRUPT 0x02
|
||||
#define RF22B_PACKET_SENT_INTERRUPT 0x04
|
||||
#define RF22B_VALID_PREAMBLE_INTERRUPT 0x40
|
||||
#define RF22B_VALID_SYNCWORD_INTERRUPT 0x80
|
||||
#define DATA_PACKAGE_SIZE 22
|
||||
#define BIN_OFF_VALUE 1150
|
||||
#define BIN_ON_VALUE 1850
|
||||
|
||||
PG_REGISTER_WITH_RESET_TEMPLATE(eleresConfig_t, eleresConfig, PG_ELERES_CONFIG, 0);
|
||||
|
||||
PG_RESET_TEMPLATE(eleresConfig_t, eleresConfig,
|
||||
.eleresFreq = SETTING_ELERES_FREQ_DEFAULT,
|
||||
.eleresTelemetryEn = SETTING_ELERES_TELEMETRY_EN_DEFAULT,
|
||||
.eleresTelemetryPower = SETTING_ELERES_TELEMETRY_POWER_DEFAULT,
|
||||
.eleresLocEn = SETTING_ELERES_LOC_EN_DEFAULT,
|
||||
.eleresLocPower = SETTING_ELERES_LOC_POWER_DEFAULT,
|
||||
.eleresLocDelay = SETTING_ELERES_LOC_DELAY_DEFAULT
|
||||
);
|
||||
|
||||
static uint8_t hoppingChannel = 1;
|
||||
static uint8_t redLed=0;
|
||||
static timeMs_t lastPackTime, nextPackTime, localizerTime;
|
||||
static uint8_t dataReady, channelHoppingTime, firstRun = 1, locForce=0;
|
||||
static uint8_t holList[16];
|
||||
static uint8_t localRssi = 0, quality;
|
||||
static uint16_t goodFrames;
|
||||
static volatile uint8_t rfMode;
|
||||
static uint8_t bkgLocEnable = 0;
|
||||
static uint8_t bkgLocChlist;
|
||||
static uint8_t bkgLocBuf[3][10];
|
||||
static uint8_t bkgLocCnt;
|
||||
static uint8_t rfTxBuffer[10];
|
||||
static uint8_t rfRxBuffer[DATA_PACKAGE_SIZE];
|
||||
static uint8_t txFull = 0;
|
||||
static uint8_t statusRegisters[2];
|
||||
static uint8_t *eleresSignaturePtr;
|
||||
static uint32_t lastIrqTime = 0;
|
||||
|
||||
typedef struct {
|
||||
uint8_t idx;
|
||||
int32_t lat; // lat 10E7
|
||||
int32_t lon; // lon 10E7
|
||||
int32_t alt; // altitude (cm)
|
||||
uint16_t heading; // <20>
|
||||
uint16_t speed; //cm/s
|
||||
uint8_t lq; // Link quality, from 0 to 4
|
||||
}__attribute__((packed)) eleres_radar_packet_t;
|
||||
|
||||
typedef struct {
|
||||
uint8_t idx;
|
||||
int32_t lat; // lat 10E7
|
||||
int32_t lon; // lon 10E7
|
||||
int32_t alt; // altitude (cm)
|
||||
}__attribute__((packed)) eleres_wp_packet_t;
|
||||
|
||||
static uint8_t rfmSpiRead(uint8_t address)
|
||||
{
|
||||
return rxSpiReadCommand(address & 0x7f, 0x00);
|
||||
}
|
||||
|
||||
static void rfmSpiWrite(uint8_t address, uint8_t data)
|
||||
{
|
||||
rxSpiWriteCommand(address | 0x80, data);
|
||||
}
|
||||
|
||||
uint16_t eleresRssi(void)
|
||||
{
|
||||
return (localRssi - 18)*1024/106;
|
||||
}
|
||||
|
||||
static void rxReset(void)
|
||||
{
|
||||
rfmSpiWrite(0x07, 1);
|
||||
rfmSpiWrite(0x08, 0x03);
|
||||
rfmSpiWrite(0x08, 0x00);
|
||||
rfmSpiWrite(0x07, 5);
|
||||
rfmSpiWrite(0x05, RF22B_RX_PACKET_RECEIVED_INTERRUPT);
|
||||
rfmSpiWrite(0x06, RF22B_VALID_SYNCWORD_INTERRUPT);
|
||||
rfmSpiRead(0x03);
|
||||
rfmSpiRead(0x04);
|
||||
}
|
||||
|
||||
|
||||
static void toReadyMode(void)
|
||||
{
|
||||
rfmSpiWrite(0x07, 1);
|
||||
rfmSpiWrite(0x05, 0);
|
||||
rfmSpiWrite(0x06, 0);
|
||||
rfmSpiRead(0x03);
|
||||
rfmSpiRead(0x04);
|
||||
rfMode = 0;
|
||||
}
|
||||
|
||||
static void toRxMode(void)
|
||||
{
|
||||
toReadyMode();
|
||||
rxReset();
|
||||
rfMode = RECEIVE;
|
||||
}
|
||||
|
||||
|
||||
static void toTxMode(uint8_t bytes_to_send)
|
||||
{
|
||||
uint8_t i;
|
||||
|
||||
toReadyMode();
|
||||
|
||||
rfmSpiWrite(0x08, 0x03);
|
||||
rfmSpiWrite(0x08, 0x00);
|
||||
|
||||
rfmSpiWrite(0x3e, bytes_to_send);
|
||||
for (i = 0; i<bytes_to_send; i++)
|
||||
rfmSpiWrite(0x7f, rfTxBuffer[i]);
|
||||
|
||||
rfmSpiWrite(0x05, RF22B_PACKET_SENT_INTERRUPT);
|
||||
rfmSpiWrite(0x06, 0);
|
||||
rfmSpiRead(0x03);
|
||||
rfmSpiRead(0x04);
|
||||
|
||||
rfmSpiWrite(0x07, 0x09);
|
||||
rfMode = TRANSMIT;
|
||||
txFull = 0;
|
||||
}
|
||||
|
||||
static void frequencyConfigurator(uint32_t frequency)
|
||||
{
|
||||
uint8_t band;
|
||||
|
||||
if (frequency<48000) {
|
||||
frequency -= 24000;
|
||||
band = frequency/1000;
|
||||
if (band>23) band = 23;
|
||||
frequency -= (1000*(uint32_t)band);
|
||||
frequency *= 64;
|
||||
band |= 0x40;
|
||||
} else {
|
||||
frequency -= 48000;
|
||||
band = frequency/2000;
|
||||
if (band>22) band = 22;
|
||||
frequency -= (2000*(uint32_t)band);
|
||||
frequency *= 32;
|
||||
band |= 0x60;
|
||||
}
|
||||
rfmSpiWrite(0x75, band);
|
||||
rfmSpiWrite(0x76, (uint16_t)frequency >> 8);
|
||||
rfmSpiWrite(0x77, (uint8_t)frequency);
|
||||
rfmSpiWrite(0x79, 0);
|
||||
}
|
||||
|
||||
static void rfm22bInitParameter(void)
|
||||
{
|
||||
int8_t i;
|
||||
static uint8_t first_init = 1;
|
||||
|
||||
static uint8_t cf1[9] = {0x00,0x01,0x00,0x7f,0x07,0x52,0x55,0xCA};
|
||||
static uint8_t cf2[6] = {0x68,0x01,0x3a,0x93,0x02,0x6b};
|
||||
static uint8_t cf3[8] = {0x0f,0x42,0x07,0x20,0x2d,0xd4,0x00,0x00};
|
||||
rfmSpiRead(0x03);
|
||||
rfmSpiRead(0x04);
|
||||
for (i = 0; i < 8; i++)
|
||||
rfmSpiWrite(0x06+i, cf1[i]);
|
||||
if (first_init) {
|
||||
first_init = 0;
|
||||
rfmSpiWrite(0x0e, 0);
|
||||
}
|
||||
|
||||
rfmSpiWrite(0x6e, 0x09);
|
||||
rfmSpiWrite(0x6f, 0xD5);
|
||||
rfmSpiWrite(0x1c, 0x02);
|
||||
rfmSpiWrite(0x70, 0x00);
|
||||
for (i=0; i<6; i++) rfmSpiWrite(0x20+i, cf2[i]);
|
||||
rfmSpiWrite(0x2a, 0x1e);
|
||||
rfmSpiWrite(0x72, 0x1F);
|
||||
rfmSpiWrite(0x30, 0x8c);
|
||||
rfmSpiWrite(0x3e, 22);
|
||||
for (i=0; i<8; i++) rfmSpiWrite(0x32+i, cf3[i]);
|
||||
for (i=0; i<4; i++) rfmSpiWrite(0x43+i, 0xff);
|
||||
rfmSpiWrite(0x6d, eleresConfig()->eleresTelemetryPower | 0x18);
|
||||
rfmSpiWrite(0x79, 0x00);
|
||||
rfmSpiWrite(0x7a, 0x04);
|
||||
rfmSpiWrite(0x71, 0x23);
|
||||
rfmSpiWrite(0x73, 0x00);
|
||||
rfmSpiWrite(0x74, 0x00);
|
||||
for (i=0; i<4; i++) {
|
||||
rfmSpiWrite(0x3a+i, eleresSignaturePtr[i]);
|
||||
rfmSpiWrite(0x3f+i, eleresSignaturePtr[i]);
|
||||
}
|
||||
|
||||
frequencyConfigurator((uint32_t)(eleresConfig()->eleresFreq * 100));
|
||||
rfmSpiRead(0x03);
|
||||
rfmSpiRead(0x04);
|
||||
}
|
||||
|
||||
static void channelHopping(uint8_t hops)
|
||||
{
|
||||
hoppingChannel += hops;
|
||||
while (hoppingChannel >= 16) hoppingChannel -= 16;
|
||||
|
||||
if (eleresConfig()->eleresTelemetryEn && eleresConfig()->eleresLocEn) {
|
||||
if (bkgLocEnable && (hoppingChannel==bkgLocChlist || hoppingChannel==(bkgLocChlist+1)%16)) {
|
||||
rfmSpiWrite(0x79,0);
|
||||
bkgLocEnable = 2;
|
||||
return;
|
||||
}
|
||||
if (bkgLocEnable == 2) bkgLocEnable = 1;
|
||||
}
|
||||
|
||||
rfmSpiWrite(0x79, holList[hoppingChannel]);
|
||||
}
|
||||
|
||||
static void telemetryRX(void)
|
||||
{
|
||||
static uint8_t telem_state;
|
||||
static int32_t presfil;
|
||||
static int16_t thempfil;
|
||||
uint8_t i, themp=90, wii_flymode=0;
|
||||
uint16_t pres,curr = abs(getAmperage()) / 10;
|
||||
union {
|
||||
int32_t val;
|
||||
uint8_t b[4];
|
||||
} cnv;
|
||||
|
||||
if (txFull)
|
||||
return;
|
||||
|
||||
memset(rfTxBuffer,0,9);
|
||||
|
||||
presfil -= presfil/4;
|
||||
presfil += baro.baroPressure;
|
||||
|
||||
int16_t temperature;
|
||||
const bool temp_valid = sensors(SENSOR_BARO) ? getBaroTemperature(&temperature) : getIMUTemperature(&temperature);
|
||||
if (!temp_valid) temperature = TEMPERATURE_INVALID_VALUE; // If temperature not valid report value outside of range
|
||||
thempfil -= thempfil/8;
|
||||
thempfil += temperature;
|
||||
|
||||
switch (telem_state++) {
|
||||
case 0:
|
||||
|
||||
if (presfil>200000) pres = presfil/4 - 50000;
|
||||
else pres = 1;
|
||||
|
||||
themp = (uint8_t)(thempfil/80 + 86);
|
||||
|
||||
if (FLIGHT_MODE(FAILSAFE_MODE)) wii_flymode = 7;
|
||||
else if (FLIGHT_MODE(MANUAL_MODE)) wii_flymode = 8;
|
||||
else if (FLIGHT_MODE(NAV_RTH_MODE)) wii_flymode = 6;
|
||||
else if (FLIGHT_MODE(NAV_POSHOLD_MODE)) wii_flymode = 5;
|
||||
else if (FLIGHT_MODE(HEADFREE_MODE)) wii_flymode = 4;
|
||||
else if (FLIGHT_MODE(NAV_ALTHOLD_MODE)) wii_flymode = 3;
|
||||
else if (FLIGHT_MODE(ANGLE_MODE) || FLIGHT_MODE(HORIZON_MODE)) wii_flymode = 2;
|
||||
else wii_flymode = 1;
|
||||
if (ARMING_FLAG(ARMED)) wii_flymode |= 0x10;
|
||||
rfTxBuffer[0] = 0x54;
|
||||
rfTxBuffer[1] = localRssi;
|
||||
rfTxBuffer[2] = quality;
|
||||
rfTxBuffer[3] = getBatteryVoltage() / 10;
|
||||
rfTxBuffer[4] = themp;
|
||||
rfTxBuffer[5] = curr & 0xff;
|
||||
rfTxBuffer[6] = pres>>8;
|
||||
rfTxBuffer[7] = pres&0xFF;
|
||||
rfTxBuffer[8] = wii_flymode;
|
||||
rfTxBuffer[8] |= ((curr>>2) & 0xC0);
|
||||
break;
|
||||
|
||||
case 1:
|
||||
if (gpsSol.llh.lat) {
|
||||
uint16_t hdop = gpsSol.hdop / 10;
|
||||
|
||||
rfTxBuffer[0] = 0x50;
|
||||
cnv.val = gpsSol.llh.lat/10;
|
||||
for (i=0; i<4; i++) rfTxBuffer[i+1] = cnv.b[i];
|
||||
cnv.val = gpsSol.llh.lon/10;
|
||||
for (i=0; i<4; i++) rfTxBuffer[i+5] = cnv.b[i];
|
||||
|
||||
rfTxBuffer[4] &= 0x0F;
|
||||
rfTxBuffer[4] |= (hdop << 4);
|
||||
rfTxBuffer[8] &= 0x1F;
|
||||
rfTxBuffer[8] |= ((hdop<<1) & 0xE0);
|
||||
break;
|
||||
}
|
||||
telem_state++;
|
||||
FALLTHROUGH;
|
||||
|
||||
case 2:
|
||||
if (sensors(SENSOR_GPS)) {
|
||||
uint16_t gpsspeed = (gpsSol.groundSpeed*9L)/250L;
|
||||
int16_t course = (gpsSol.groundCourse/10 + 360)%360;
|
||||
int32_t alt = getEstimatedActualPosition(Z);
|
||||
uint16_t tim = 0;
|
||||
|
||||
rfTxBuffer[0] = 0x47;
|
||||
rfTxBuffer[1] = (STATE(GPS_FIX)<<4) | (gpsSol.numSat & 0x0F);
|
||||
if (gpsSol.numSat > 15) rfTxBuffer[1] |= 0x80;
|
||||
rfTxBuffer[2] = ((course>>8) & 0x0F) | ((gpsspeed>>4) & 0xF0);
|
||||
rfTxBuffer[3] = course & 0xFF;
|
||||
rfTxBuffer[4] = gpsspeed & 0xFF;
|
||||
|
||||
rfTxBuffer[5] = (alt/100) >>8;
|
||||
rfTxBuffer[6] = (alt/100) & 0xFF;
|
||||
|
||||
rfTxBuffer[7] = tim>>8;
|
||||
rfTxBuffer[8] = tim&0xFF;
|
||||
break;
|
||||
}
|
||||
telem_state++;
|
||||
FALLTHROUGH;
|
||||
|
||||
default:
|
||||
rfTxBuffer[0] = 'D';
|
||||
memcpy(rfTxBuffer+1,&debug[0],2);
|
||||
memcpy(rfTxBuffer+3,&debug[1],2);
|
||||
memcpy(rfTxBuffer+5,&debug[2],2);
|
||||
memcpy(rfTxBuffer+7,&debug[3],2);
|
||||
telem_state = 0;
|
||||
break;
|
||||
}
|
||||
txFull = 1;
|
||||
}
|
||||
|
||||
//because we shared SPI bus I can't read data in real IRQ, so need to probe this pin from main idle
|
||||
rx_spi_received_e eleresDataReceived(uint8_t *payload, uint16_t *linkQuality)
|
||||
{
|
||||
UNUSED(payload);
|
||||
|
||||
statusRegisters[0] = 0;
|
||||
statusRegisters[1] = 0;
|
||||
|
||||
if (linkQuality) {
|
||||
*linkQuality = eleresRssi();
|
||||
}
|
||||
|
||||
if (rxSpiCheckIrq())
|
||||
{
|
||||
lastIrqTime = millis();
|
||||
statusRegisters[0] = rfmSpiRead(0x03);
|
||||
statusRegisters[1] = rfmSpiRead(0x04);
|
||||
//only if RC frame received
|
||||
if (statusRegisters[0] & RF22B_RX_PACKET_RECEIVED_INTERRUPT) {
|
||||
return RX_SPI_RECEIVED_DATA;
|
||||
}
|
||||
}
|
||||
|
||||
eleresSetRcDataFromPayload(NULL,NULL);
|
||||
|
||||
return RX_SPI_RECEIVED_NONE;
|
||||
}
|
||||
|
||||
static void parseStatusRegister(const uint8_t *payload)
|
||||
{
|
||||
UNUSED(payload);
|
||||
static uint16_t rssifil;
|
||||
const timeMs_t irq_time = millis();
|
||||
|
||||
if ((rfMode & RECEIVE) && (statusRegisters[0] & RF22B_RX_PACKET_RECEIVED_INTERRUPT))
|
||||
rfMode |= RECEIVED;
|
||||
if ((rfMode & TRANSMIT) && (statusRegisters[0] & RF22B_PACKET_SENT_INTERRUPT))
|
||||
rfMode |= TRANSMITTED;
|
||||
if ((rfMode & RECEIVE) && (statusRegisters[1] & RF22B_VALID_SYNCWORD_INTERRUPT))
|
||||
rfMode |= PREAMBLE;
|
||||
|
||||
if (rfMode & RECEIVED) {
|
||||
if (bkgLocEnable < 2) {
|
||||
lastPackTime = irq_time;
|
||||
nextPackTime = irq_time + channelHoppingTime;
|
||||
}
|
||||
rxSpiReadCommandMulti(0x7f,0x00,rfRxBuffer,DATA_PACKAGE_SIZE);
|
||||
rxReset();
|
||||
rfMode = RECEIVE;
|
||||
if ((rfRxBuffer[0] & 127) == 'S') {
|
||||
firstRun = 0;
|
||||
goodFrames++;
|
||||
|
||||
if ((rfRxBuffer[21] & 0xF0) == 0x20)
|
||||
hoppingChannel = rfRxBuffer[21] & 0x0F;
|
||||
|
||||
channelHoppingTime = (rfRxBuffer[20] & 0x0F)+18;
|
||||
dataReady |= DATA_FLAG;
|
||||
} else if ((rfRxBuffer[0] & 127) == 'R') { //radar poi info
|
||||
eleres_radar_packet_t p;
|
||||
uint8_t idx=0;
|
||||
|
||||
firstRun = 0;
|
||||
goodFrames++;
|
||||
|
||||
if ((rfRxBuffer[21] & 0xF0) == 0x20)
|
||||
hoppingChannel = rfRxBuffer[21] & 0x0F;
|
||||
channelHoppingTime = (rfRxBuffer[20] & 0x0F)+18;
|
||||
|
||||
//parse plane info
|
||||
memcpy(&p, &rfRxBuffer[1], sizeof(p));
|
||||
idx = MIN(p.idx, RADAR_MAX_POIS - 1); // Radar poi number, 0 to 3
|
||||
radar_pois[idx].gps.lat = p.lat;
|
||||
radar_pois[idx].gps.lon = p.lon;
|
||||
radar_pois[idx].gps.alt = p.alt;
|
||||
radar_pois[idx].heading = p.heading;
|
||||
radar_pois[idx].speed = p.speed;
|
||||
radar_pois[idx].lq = p.lq;
|
||||
if (p.lat == 0 || p.lon == 0)
|
||||
radar_pois[idx].state = 0;
|
||||
else
|
||||
radar_pois[idx].state = 1;
|
||||
} else if ((rfRxBuffer[0] & 127) == 'W') { //WP info
|
||||
eleres_wp_packet_t p;
|
||||
navWaypoint_t tp; //targetPoint
|
||||
|
||||
firstRun = 0;
|
||||
goodFrames++;
|
||||
|
||||
if ((rfRxBuffer[21] & 0xF0) == 0x20)
|
||||
hoppingChannel = rfRxBuffer[21] & 0x0F;
|
||||
channelHoppingTime = (rfRxBuffer[20] & 0x0F)+18;
|
||||
|
||||
//parse plane info
|
||||
memcpy(&p, &rfRxBuffer[1], sizeof(p));
|
||||
|
||||
tp.action = NAV_WP_ACTION_WAYPOINT;
|
||||
tp.alt = p.alt;
|
||||
tp.lat = p.lat;
|
||||
tp.lon = p.lon;
|
||||
setWaypoint(p.idx, &tp);
|
||||
} else if (eleresConfig()->eleresLocEn && eleresConfig()->eleresTelemetryEn && bkgLocEnable==2) {
|
||||
if ((rfRxBuffer[0] == 'H' && rfRxBuffer[2] == 'L') ||
|
||||
rfRxBuffer[0]=='T' || rfRxBuffer[0]=='P' || rfRxBuffer[0]=='G') {
|
||||
if (bkgLocCnt==0) bkgLocCnt = 200;
|
||||
toReadyMode();
|
||||
bkgLocEnable = 0;
|
||||
channelHopping(0);
|
||||
bkgLocEnable = 2;
|
||||
dataReady |= RELAY_FLAG;
|
||||
}
|
||||
} else if (eleresConfig()->eleresLocEn) {
|
||||
if (rfRxBuffer[0] == 0x4c && rfRxBuffer[1] == 0x4f && rfRxBuffer[2] == 0x43) {
|
||||
localizerTime = irq_time;
|
||||
locForce = 1;
|
||||
localRssi = 0x18;
|
||||
}
|
||||
}
|
||||
|
||||
if ((dataReady & LOCALIZER_FLAG)==0) {
|
||||
if (eleresConfig()->eleresTelemetryEn)
|
||||
toTxMode(9);
|
||||
else
|
||||
channelHopping(1);
|
||||
}
|
||||
}
|
||||
|
||||
if (rfMode & TRANSMITTED) {
|
||||
toReadyMode();
|
||||
if (dataReady & LOCALIZER_FLAG) {
|
||||
rfmSpiWrite(0x79, holList[0]);
|
||||
} else if (irq_time-lastPackTime <= 1500 && bkgLocEnable<2)
|
||||
channelHopping(1);
|
||||
toRxMode();
|
||||
}
|
||||
|
||||
if (rfMode & PREAMBLE) {
|
||||
uint8_t rssitmp = rfmSpiRead(0x26);
|
||||
if (eleresConfig()->eleresLocEn && eleresConfig()->eleresTelemetryEn && bkgLocEnable==2) {
|
||||
if (rssitmp>124) rssitmp = 124;
|
||||
if (rssitmp<18) rssitmp = 18;
|
||||
bkgLocBuf[0][1] = rssitmp + 128;
|
||||
} else {
|
||||
rssifil -= rssifil/8;
|
||||
rssifil += rssitmp;
|
||||
localRssi = (rssifil/8 * quality / 100)+10;
|
||||
if (localRssi>124) localRssi = 124;
|
||||
if (localRssi<18) localRssi = 18;
|
||||
}
|
||||
rfMode &= ~PREAMBLE;
|
||||
}
|
||||
}
|
||||
|
||||
void eleresSetRcDataFromPayload(uint16_t *rcData, const uint8_t *payload)
|
||||
{
|
||||
UNUSED(payload);
|
||||
uint16_t rcData4Values[RC_CHANS];
|
||||
static uint8_t rx_frames, loc_cnt;
|
||||
uint8_t channel_count;
|
||||
uint8_t i,n;
|
||||
uint16_t temp_int;
|
||||
static timeMs_t qtest_time, guard_time, led_time;
|
||||
timeMs_t cr_time = millis();
|
||||
int red_led_local = 0;
|
||||
//uint8_t res = RX_FRAME_PENDING;
|
||||
|
||||
parseStatusRegister(statusRegisters);
|
||||
|
||||
if (cr_time < (led_time + 500))
|
||||
red_led_local = 0;
|
||||
else if (cr_time < (led_time + 1000))
|
||||
red_led_local = 1;
|
||||
else
|
||||
led_time = cr_time;
|
||||
|
||||
//watch IRQ - if not received, restart RFM
|
||||
if (eleresConfig()->eleresTelemetryEn && millis() - lastIrqTime > 2000)
|
||||
{
|
||||
if (lastIrqTime < 4000)
|
||||
{
|
||||
rfmSpiWrite(0x07, 0x80); //restart rfm22 in case of problems only at startup
|
||||
delay(1);
|
||||
}
|
||||
|
||||
rfm22bInitParameter();
|
||||
toRxMode();
|
||||
lastIrqTime = millis();
|
||||
}
|
||||
|
||||
if ((dataReady & LOCALIZER_FLAG) == 0) {
|
||||
if (cr_time > nextPackTime+2) {
|
||||
if ((cr_time-lastPackTime > 1500) || firstRun) {
|
||||
localRssi = 18;
|
||||
rfm22bInitParameter();
|
||||
toRxMode();
|
||||
channelHopping(15);
|
||||
nextPackTime += 17L*channelHoppingTime;
|
||||
if (eleresConfig()->eleresTelemetryEn) {
|
||||
telemetryRX();
|
||||
toTxMode(9);
|
||||
}
|
||||
// res = RX_FRAME_FAILSAFE;
|
||||
} else {
|
||||
|
||||
if (cr_time-lastPackTime > 3*channelHoppingTime) {
|
||||
red_led_local=1;
|
||||
if (localRssi > 0x18)
|
||||
localRssi--;
|
||||
}
|
||||
toRxMode();
|
||||
channelHopping(1);
|
||||
nextPackTime += channelHoppingTime;
|
||||
}
|
||||
}
|
||||
if (cr_time > qtest_time) {
|
||||
qtest_time = cr_time + 500;
|
||||
quality = goodFrames * 100 / (500/channelHoppingTime);
|
||||
if (quality > 100) quality = 100;
|
||||
goodFrames = 0;
|
||||
}
|
||||
}
|
||||
|
||||
if ((dataReady & 0x03) == DATA_FLAG && rcData != NULL) {
|
||||
if ((dataReady & RELAY_FLAG)==0) {
|
||||
channel_count = rfRxBuffer[20] >> 4;
|
||||
if (channel_count < 4) channel_count = 4;
|
||||
if (channel_count > RC_CHANS) channel_count = 12;
|
||||
for (i = 0; i<channel_count; i++) {
|
||||
temp_int = rfRxBuffer[i+1];
|
||||
if (i%2 == 0)
|
||||
temp_int |= ((unsigned int)rfRxBuffer[i/2 + 13] << 4) & 0x0F00;
|
||||
else
|
||||
temp_int |= ((unsigned int)rfRxBuffer[i/2 + 13] << 8) & 0x0F00;
|
||||
if ((temp_int>799) && (temp_int<2201)) rcData4Values[i] = temp_int;
|
||||
}
|
||||
n = rfRxBuffer[19];
|
||||
for (i=channel_count; i < channel_count+5; i++) {
|
||||
if (i > 11) break;
|
||||
if (n & 0x01) temp_int = BIN_ON_VALUE;
|
||||
else temp_int = BIN_OFF_VALUE;
|
||||
rcData4Values[i] = temp_int;
|
||||
n >>= 1;
|
||||
}
|
||||
for (; i<RC_CHANS; i++) rcData4Values[i]=1500;
|
||||
for (i=0; i<RC_CHANS; i++) {
|
||||
temp_int = rcData4Values[i];
|
||||
if (temp_int < rcData[i] -3) rcData[i] = temp_int+2;
|
||||
if (temp_int > rcData[i] +3) rcData[i] = temp_int-2;
|
||||
}
|
||||
|
||||
localizerTime = cr_time + (1000L*eleresConfig()->eleresLocDelay);
|
||||
|
||||
if (eleresConfig()->eleresTelemetryEn) {
|
||||
if (eleresConfig()->eleresLocEn) {
|
||||
if (bkgLocEnable == 0) bkgLocCnt=0;
|
||||
if (bkgLocCnt) bkgLocCnt--;
|
||||
|
||||
if (bkgLocCnt<128)
|
||||
telemetryRX();
|
||||
else
|
||||
memcpy(rfTxBuffer, bkgLocBuf[bkgLocCnt%3], 9);
|
||||
} else
|
||||
telemetryRX();
|
||||
}
|
||||
|
||||
if (eleresConfig()->eleresTelemetryEn)
|
||||
telemetryRX();
|
||||
}
|
||||
dataReady &= 0xFC;
|
||||
led_time = cr_time;
|
||||
//res = RX_FRAME_COMPLETE;
|
||||
}
|
||||
|
||||
if (eleresConfig()->eleresLocEn) {
|
||||
if ((dataReady & 0x03)==(DATA_FLAG | LOCALIZER_FLAG) && rfRxBuffer[19]<128) {
|
||||
if (rx_frames == 0) guard_time = lastPackTime;
|
||||
if (rx_frames < 250) {
|
||||
rx_frames++;
|
||||
}
|
||||
if (rx_frames > 20 && cr_time-guard_time > (locForce?5000:20000)) {
|
||||
dataReady = 0;
|
||||
localizerTime = cr_time + (1000L*eleresConfig()->eleresLocDelay);
|
||||
rfm22bInitParameter();
|
||||
channelHopping(1);
|
||||
rx_frames = 0;
|
||||
|
||||
if (locForce && eleresConfig()->eleresTelemetryEn) {
|
||||
bkgLocEnable = 1;
|
||||
temp_int = 0;
|
||||
for (i=0; i<16; i++) {
|
||||
uint16_t mult = holList[i] * holList[(i+1)%16];
|
||||
if (mult > temp_int) {
|
||||
temp_int = mult;
|
||||
bkgLocChlist = i;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
if (cr_time-lastPackTime > 8000) {
|
||||
rx_frames = 0;
|
||||
}
|
||||
if (!ARMING_FLAG(ARMED) && cr_time > localizerTime) {
|
||||
if ((dataReady & LOCALIZER_FLAG)==0) {
|
||||
rfm22bInitParameter();
|
||||
rfmSpiWrite(0x6d, eleresConfig()->eleresLocPower);
|
||||
}
|
||||
dataReady &= 0xFB;
|
||||
dataReady |= LOCALIZER_FLAG;
|
||||
localizerTime = cr_time+35;
|
||||
rfmSpiWrite(0x79, 0);
|
||||
red_led_local = 1;
|
||||
led_time = cr_time;
|
||||
|
||||
bkgLocEnable = 0;
|
||||
if (!(++loc_cnt & 1) && eleresConfig()->eleresTelemetryEn) {
|
||||
telemetryRX();
|
||||
toTxMode(9);
|
||||
} else {
|
||||
rfTxBuffer[0] = 0x48;
|
||||
rfTxBuffer[1] = 0x45;
|
||||
rfTxBuffer[2] = 0x4c;
|
||||
rfTxBuffer[3] = 0x50;
|
||||
rfTxBuffer[4] = 0x21;
|
||||
toTxMode(5);
|
||||
}
|
||||
}
|
||||
|
||||
if ((ARMING_FLAG(ARMED) || firstRun) && (dataReady & LOCALIZER_FLAG)==0)
|
||||
localizerTime = cr_time + (1000L*eleresConfig()->eleresLocDelay);
|
||||
|
||||
if (eleresConfig()->eleresTelemetryEn)
|
||||
if (dataReady & RELAY_FLAG) {
|
||||
if (rfRxBuffer[0]=='H') bkgLocBuf[0][0]='T';
|
||||
if (rfRxBuffer[0]=='T') {
|
||||
bkgLocBuf[0][0]='T';
|
||||
memcpy(bkgLocBuf[0]+2, rfRxBuffer+2, 7);
|
||||
}
|
||||
if (rfRxBuffer[0]=='P') memcpy(bkgLocBuf[1], rfRxBuffer, 9);
|
||||
if (rfRxBuffer[0]=='G') memcpy(bkgLocBuf[2], rfRxBuffer, 9);
|
||||
dataReady = 0;
|
||||
}
|
||||
}
|
||||
|
||||
if (red_led_local) {
|
||||
RED_LED_ON;
|
||||
} else {
|
||||
RED_LED_OFF;
|
||||
}
|
||||
//return res;
|
||||
}
|
||||
|
||||
static uint8_t checkChannel(uint8_t channel, uint8_t *hop_lst)
|
||||
{
|
||||
uint8_t new_channel, count = 0, high = 0, i;
|
||||
for (i=0; i<16; i++) {
|
||||
if (high<hop_lst[i]) high = hop_lst[i];
|
||||
if (channel==hop_lst[i]) count++;
|
||||
}
|
||||
if (count>0) new_channel = high+2;
|
||||
else new_channel = channel;
|
||||
return new_channel%255;
|
||||
}
|
||||
|
||||
static void bindChannels(const uint8_t* RF_HEAD, uint8_t* hop_lst)
|
||||
{
|
||||
uint8_t n;
|
||||
|
||||
memset(hop_lst, 0x00, 16);
|
||||
|
||||
for (int j=0; j<4; j++) {
|
||||
for (int i=0; i<4; i++) {
|
||||
n = RF_HEAD[i]%128;
|
||||
if (j==3) n /= 5;
|
||||
else n /= j+1;
|
||||
hop_lst[4*j+i] = checkChannel(n,hop_lst);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void eleresInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig)
|
||||
{
|
||||
UNUSED(rxConfig);
|
||||
rxConfigMutable()->rx_spi_protocol = RFM22_ELERES;
|
||||
rxRuntimeConfig->channelCount = RC_CHANS;
|
||||
|
||||
rfmSpiWrite(0x07, 0x80);
|
||||
delay(100);
|
||||
|
||||
eleresSignaturePtr = (uint8_t*)&eleresConfig()->eleresSignature;
|
||||
|
||||
rfm22bInitParameter();
|
||||
bindChannels(eleresSignaturePtr,holList);
|
||||
channelHoppingTime = 33;
|
||||
toRxMode();
|
||||
channelHopping(1);
|
||||
rfMode = RECEIVE;
|
||||
localizerTime = millis() + (1000L * eleresConfig()->eleresLocDelay);
|
||||
}
|
||||
|
||||
uint8_t eleresBind(void)
|
||||
{
|
||||
static uint8_t eleres_signature_old[4];
|
||||
static uint8_t eleres_signature_OK_count = 0;
|
||||
uint16_t timeout = 10000;
|
||||
uint8_t i;
|
||||
|
||||
eleresSignaturePtr[0] = 0x42;
|
||||
eleresSignaturePtr[1] = 0x49;
|
||||
eleresSignaturePtr[2] = 0x4e;
|
||||
eleresSignaturePtr[3] = 0x44;
|
||||
|
||||
rfm22bInitParameter();
|
||||
bindChannels(eleresSignaturePtr,holList);
|
||||
channelHoppingTime = 33;
|
||||
RED_LED_OFF;
|
||||
while (timeout--) {
|
||||
eleresDataReceived(NULL, NULL);
|
||||
eleresSetRcDataFromPayload(NULL,NULL);
|
||||
if (rfRxBuffer[0]==0x42) {
|
||||
for (i=0; i<4; i++) {
|
||||
if (rfRxBuffer[i+1]==eleres_signature_old[i]) eleres_signature_OK_count++;
|
||||
else eleres_signature_OK_count = 0;
|
||||
}
|
||||
for (i=0; i<4; i++) eleres_signature_old[i] = rfRxBuffer[i+1];
|
||||
if (eleres_signature_OK_count>200) {
|
||||
for (i=0; i<4; i++)
|
||||
eleresSignaturePtr[i] = eleres_signature_old[i];
|
||||
RED_LED_OFF;
|
||||
saveConfigAndNotify();
|
||||
rfm22bInitParameter();
|
||||
return 0;
|
||||
}
|
||||
rfRxBuffer[0] = 0;
|
||||
}
|
||||
delay(1);
|
||||
}
|
||||
rfm22bInitParameter();
|
||||
return 1;
|
||||
}
|
||||
|
||||
#endif //RX_ELERES
|
|
@ -1,22 +0,0 @@
|
|||
#pragma once
|
||||
#include "config/parameter_group.h"
|
||||
#include "rx/rx_spi.h"
|
||||
|
||||
void eleresSetRcDataFromPayload(uint16_t *rcData, const uint8_t *payload);
|
||||
uint8_t eleresBind(void);
|
||||
uint16_t eleresRssi(void);
|
||||
rx_spi_received_e eleresDataReceived(uint8_t *payload, uint16_t *linkQuality);
|
||||
void eleresInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig);
|
||||
|
||||
typedef struct
|
||||
{
|
||||
float eleresFreq;
|
||||
uint8_t eleresTelemetryEn;
|
||||
uint8_t eleresTelemetryPower;
|
||||
uint8_t eleresLocEn;
|
||||
uint8_t eleresLocPower;
|
||||
uint16_t eleresLocDelay;
|
||||
uint32_t eleresSignature;
|
||||
} eleresConfig_t;
|
||||
|
||||
PG_DECLARE(eleresConfig_t, eleresConfig);
|
|
@ -37,7 +37,6 @@
|
|||
|
||||
|
||||
#include "drivers/adc.h"
|
||||
#include "drivers/rx_spi.h"
|
||||
#include "drivers/serial.h"
|
||||
#include "drivers/time.h"
|
||||
|
||||
|
@ -52,14 +51,12 @@
|
|||
|
||||
#include "rx/rx.h"
|
||||
#include "rx/crsf.h"
|
||||
#include "rx/eleres.h"
|
||||
#include "rx/ibus.h"
|
||||
#include "rx/jetiexbus.h"
|
||||
#include "rx/fport.h"
|
||||
#include "rx/fport2.h"
|
||||
#include "rx/msp.h"
|
||||
#include "rx/msp_override.h"
|
||||
#include "rx/rx_spi.h"
|
||||
#include "rx/sbus.h"
|
||||
#include "rx/spektrum.h"
|
||||
#include "rx/srxl2.h"
|
||||
|
@ -69,8 +66,6 @@
|
|||
#include "rx/ghst.h"
|
||||
#include "rx/mavlink.h"
|
||||
|
||||
//#define DEBUG_RX_SIGNAL_LOSS
|
||||
|
||||
const char rcChannelLetters[] = "AERT";
|
||||
|
||||
static uint16_t rssi = 0; // range: [0;1023]
|
||||
|
@ -108,11 +103,8 @@ rxLinkStatistics_t rxLinkStatistics;
|
|||
rxRuntimeConfig_t rxRuntimeConfig;
|
||||
static uint8_t rcSampleIndex = 0;
|
||||
|
||||
PG_REGISTER_WITH_RESET_TEMPLATE(rxConfig_t, rxConfig, PG_RX_CONFIG, 10);
|
||||
PG_REGISTER_WITH_RESET_TEMPLATE(rxConfig_t, rxConfig, PG_RX_CONFIG, 11);
|
||||
|
||||
#ifndef RX_SPI_DEFAULT_PROTOCOL
|
||||
#define RX_SPI_DEFAULT_PROTOCOL 0
|
||||
#endif
|
||||
#ifndef SERIALRX_PROVIDER
|
||||
#define SERIALRX_PROVIDER 0
|
||||
#endif
|
||||
|
@ -127,9 +119,6 @@ PG_RESET_TEMPLATE(rxConfig_t, rxConfig,
|
|||
.rcmap = {0, 1, 3, 2}, // Default to AETR map
|
||||
.halfDuplex = SETTING_SERIALRX_HALFDUPLEX_DEFAULT,
|
||||
.serialrx_provider = SERIALRX_PROVIDER,
|
||||
#ifdef USE_RX_SPI
|
||||
.rx_spi_protocol = RX_SPI_DEFAULT_PROTOCOL,
|
||||
#endif
|
||||
#ifdef USE_SPEKTRUM_BIND
|
||||
.spektrum_sat_bind = SETTING_SPEKTRUM_SAT_BIND_DEFAULT,
|
||||
#endif
|
||||
|
@ -331,16 +320,6 @@ void rxInit(void)
|
|||
break;
|
||||
#endif
|
||||
|
||||
#ifdef USE_RX_SPI
|
||||
case RX_TYPE_SPI:
|
||||
if (!rxSpiInit(rxConfig(), &rxRuntimeConfig)) {
|
||||
rxConfigMutable()->receiverType = RX_TYPE_NONE;
|
||||
rxRuntimeConfig.rcReadRawFn = nullReadRawRC;
|
||||
rxRuntimeConfig.rcFrameStatusFn = nullFrameStatus;
|
||||
}
|
||||
break;
|
||||
#endif
|
||||
|
||||
default:
|
||||
case RX_TYPE_NONE:
|
||||
rxConfigMutable()->receiverType = RX_TYPE_NONE;
|
||||
|
|
|
@ -64,8 +64,7 @@ typedef enum {
|
|||
typedef enum {
|
||||
RX_TYPE_NONE = 0,
|
||||
RX_TYPE_SERIAL = 1,
|
||||
RX_TYPE_MSP = 2,
|
||||
RX_TYPE_SPI = 3
|
||||
RX_TYPE_MSP = 2
|
||||
} rxReceiverType_e;
|
||||
|
||||
typedef enum {
|
||||
|
@ -115,11 +114,6 @@ typedef struct rxConfig_s {
|
|||
uint8_t serialrx_provider; // Type of UART-based receiver (rxSerialReceiverType_e enum). Only used if receiverType is RX_TYPE_SERIAL
|
||||
uint8_t serialrx_inverted; // Flip the default inversion of the protocol - e.g. sbus (Futaba, FrSKY) is inverted if this is false, uninverted if it's true. Support for uninverted OpenLRS (and modified FrSKY) receivers.
|
||||
uint8_t halfDuplex; // allow rx to operate in half duplex mode. From tristate_e.
|
||||
#ifdef USE_RX_SPI
|
||||
uint8_t rx_spi_protocol; // type of SPI receiver protocol (rx_spi_protocol_e enum). Only used if receiverType is RX_TYPE_SPI
|
||||
uint32_t rx_spi_id;
|
||||
uint8_t rx_spi_rf_channel_count;
|
||||
#endif
|
||||
#ifdef USE_SPEKTRUM_BIND
|
||||
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
|
||||
|
|
|
@ -1,122 +0,0 @@
|
|||
/*
|
||||
* This file is part of Cleanflight.
|
||||
*
|
||||
* Cleanflight is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* Cleanflight is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
|
||||
#include <platform.h>
|
||||
|
||||
#ifdef USE_RX_SPI
|
||||
|
||||
#include "build/build_config.h"
|
||||
|
||||
#include "common/utils.h"
|
||||
|
||||
#include "config/feature.h"
|
||||
|
||||
#include "drivers/rx_nrf24l01.h"
|
||||
|
||||
#include "fc/config.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
#include "rx/rx_spi.h"
|
||||
#include "rx/eleres.h"
|
||||
#include "rx/nrf24_cx10.h"
|
||||
#include "rx/nrf24_syma.h"
|
||||
#include "rx/nrf24_v202.h"
|
||||
#include "rx/nrf24_h8_3d.h"
|
||||
#include "rx/nrf24_inav.h"
|
||||
|
||||
|
||||
static 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 void (*protocolInitPtr)(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig);
|
||||
typedef rx_spi_received_e (*protocolDataReceivedPtr)(uint8_t *payload, uint16_t *linkQuality);
|
||||
typedef void (*protocolSetRcDataFromPayloadPtr)(uint16_t *rcData, const uint8_t *payload);
|
||||
|
||||
static protocolInitPtr protocolInit;
|
||||
static protocolDataReceivedPtr protocolDataReceived;
|
||||
static protocolSetRcDataFromPayloadPtr protocolSetRcDataFromPayload;
|
||||
|
||||
STATIC_UNIT_TESTED uint16_t rxSpiReadRawRC(const rxRuntimeConfig_t *rxRuntimeConfig, uint8_t channel)
|
||||
{
|
||||
BUILD_BUG_ON(NRF24L01_MAX_PAYLOAD_SIZE > RX_SPI_MAX_PAYLOAD_SIZE);
|
||||
if (channel >= rxRuntimeConfig->channelCount) {
|
||||
return 0;
|
||||
}
|
||||
if (rxSpiNewPacketAvailable) {
|
||||
protocolSetRcDataFromPayload(rxSpiRcData, rxSpiPayload);
|
||||
rxSpiNewPacketAvailable = false;
|
||||
}
|
||||
return rxSpiRcData[channel];
|
||||
}
|
||||
|
||||
STATIC_UNIT_TESTED bool rxSpiSetProtocol(rx_spi_protocol_e protocol)
|
||||
{
|
||||
switch (protocol) {
|
||||
default:
|
||||
#ifdef USE_RX_ELERES
|
||||
case RFM22_ELERES:
|
||||
protocolInit = eleresInit;
|
||||
protocolDataReceived = eleresDataReceived;
|
||||
protocolSetRcDataFromPayload = eleresSetRcDataFromPayload;
|
||||
break;
|
||||
#endif
|
||||
}
|
||||
return true;
|
||||
}
|
||||
|
||||
/*
|
||||
* Returns true if the RX has received new data.
|
||||
* Called from updateRx in rx.c, updateRx called from taskUpdateRxCheck.
|
||||
* If taskUpdateRxCheck returns true, then taskUpdateRxMain will shortly be called.
|
||||
*/
|
||||
static uint8_t rxSpiFrameStatus(rxRuntimeConfig_t *rxRuntimeConfig)
|
||||
{
|
||||
uint16_t linkQuality = 0;
|
||||
|
||||
if (protocolDataReceived(&rxSpiPayload[0], &linkQuality) == RX_SPI_RECEIVED_DATA) {
|
||||
lqTrackerSet(rxRuntimeConfig->lqTracker, linkQuality);
|
||||
rxSpiNewPacketAvailable = true;
|
||||
return RX_FRAME_COMPLETE;
|
||||
}
|
||||
return RX_FRAME_PENDING;
|
||||
}
|
||||
|
||||
/*
|
||||
* Set and initialize the RX protocol
|
||||
*/
|
||||
bool rxSpiInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig)
|
||||
{
|
||||
bool ret = false;
|
||||
|
||||
rxSpiDeviceInit();
|
||||
if (rxSpiSetProtocol(rxConfig->rx_spi_protocol)) {
|
||||
protocolInit(rxConfig, rxRuntimeConfig);
|
||||
ret = true;
|
||||
}
|
||||
|
||||
rxRuntimeConfig->rxRefreshRate = 10000;
|
||||
rxSpiNewPacketAvailable = false;
|
||||
rxRuntimeConfig->rcReadRawFn = rxSpiReadRawRC;
|
||||
rxRuntimeConfig->rcFrameStatusFn = rxSpiFrameStatus;
|
||||
|
||||
return ret;
|
||||
}
|
||||
#endif
|
|
@ -1,64 +0,0 @@
|
|||
/*
|
||||
* This file is part of Cleanflight.
|
||||
*
|
||||
* Cleanflight is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* Cleanflight is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
|
||||
typedef enum {
|
||||
RFM22_ELERES = 0,
|
||||
NRF24RX_PROTOCOL_COUNT
|
||||
} rx_spi_protocol_e;
|
||||
|
||||
typedef enum {
|
||||
RX_SPI_RECEIVED_NONE = 0,
|
||||
RX_SPI_RECEIVED_BIND,
|
||||
RX_SPI_RECEIVED_DATA
|
||||
} rx_spi_received_e;
|
||||
|
||||
// RC channels in AETR order
|
||||
typedef enum {
|
||||
RC_SPI_ROLL = 0,
|
||||
RC_SPI_PITCH,
|
||||
RC_SPI_THROTTLE,
|
||||
RC_SPI_YAW,
|
||||
RC_SPI_AUX1,
|
||||
RC_SPI_AUX2,
|
||||
RC_SPI_AUX3,
|
||||
RC_SPI_AUX4,
|
||||
RC_SPI_AUX5,
|
||||
RC_SPI_AUX6,
|
||||
RC_SPI_AUX7,
|
||||
RC_SPI_AUX8,
|
||||
RC_SPI_AUX9,
|
||||
RC_SPI_AUX10,
|
||||
RC_SPI_AUX11,
|
||||
RC_SPI_AUX12,
|
||||
RC_SPI_AUX13,
|
||||
RC_SPI_AUX14
|
||||
} rc_spi_aetr_e;
|
||||
|
||||
// RC channels as used by deviation
|
||||
#define RC_CHANNEL_RATE RC_SPI_AUX1
|
||||
#define RC_CHANNEL_FLIP RC_SPI_AUX2
|
||||
#define RC_CHANNEL_PICTURE RC_SPI_AUX3
|
||||
#define RC_CHANNEL_VIDEO RC_SPI_AUX4
|
||||
#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);
|
Loading…
Add table
Add a link
Reference in a new issue