diff --git a/.gitignore b/.gitignore index b88f771e8b..0093a3cc57 100644 --- a/.gitignore +++ b/.gitignore @@ -65,6 +65,7 @@ paparazzi.sublime-workspace /conf/maps.xml /conf/gps/ublox_conf !/conf/simulator/gazebo/**/*.config +/conf/tools/blacklisted # /doc/pprz_algebra/ /doc/pprz_algebra/headfile.log diff --git a/conf/Makefile.stm32-upload b/conf/Makefile.stm32-upload index d6084d7ca0..35ed7f8a76 100644 --- a/conf/Makefile.stm32-upload +++ b/conf/Makefile.stm32-upload @@ -51,6 +51,7 @@ ifdef DFU_PRODUCT DFU_PRODUCT_CMD = --product=$(DFU_PRODUCT) endif upload: $(OBJDIR)/$(TARGET).bin + $(DFU_PRE_UPLOAD_CMD) @echo "Using stm32 mem dfu loader" $(PYTHON) $(PAPARAZZI_SRC)/sw/tools/dfu/stm32_mem.py $(DFU_PRODUCT_CMD) $(DFU_ADDR_CMD) $^ @@ -72,6 +73,7 @@ DFUSE_VERIFY_ADDRESS = $(DFU_ADDR):$(DFU_SIZE) endif upload: $(OBJDIR)/$(TARGET).bin + $(DFU_UTIL_PRE_UPLOAD_CMD) @echo "Using dfu-util at $(DFU_ADDR)" $(Q)dfu-util -d 0483:df11 -c 1 -i 0 -a 0 -s $(DFU_ADDR) -D $^ ifeq ($(VERIFY),1) diff --git a/conf/airframes/examples/trashcan.xml b/conf/airframes/examples/trashcan.xml new file mode 100644 index 0000000000..d1da65ea7b --- /dev/null +++ b/conf/airframes/examples/trashcan.xml @@ -0,0 +1,490 @@ + + + +* Airframe for the regular "Trashcan" Quadrotor frame equipped with to validate all onboard functionally. + + Autopilot: Default Crazybee F4 Pro STM32F4 and all that comes with it + + Actuators: Default onboard Blheli S ESCs see http://wiki.paparazziuav.org/wiki/Subsystem/actuators#PWM + + Telemetry: Default WiFi Via ESP8266 see + + RC RX: OpenRX FrSky compatible over air 2.4Ghz CPPM out on LED pin + + NOTES: + + All set to expect flying on 2s LiPo battery, 1s LiPo battery possible but no gains set (yet..) + + Removed Camera and Video TX to be replaced by a JeVois (www.jevois.org) camera on Uart1 + + RC control also possible via wifi telemetry module + + Vison: added a JeVois on UART1 TX/RX + + RC RX: OpenRX FrSky compatible over air 2.4Ghz CPPM out, + + Wifi telemetry module also allows RC + + WIP: + + GPS: uBlox SAM M8Q with Magneto n Baro GNSS + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+ + +
+ + + + + + + + + + + +
+ + + + + + +
+ +
+ + + + + + + + + + + + + + + + + + + + + + +
+ +
+ + + + + + + + + + + + + + + + + + + + + + + +
+ + +
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+ + + + + + +
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+ +
+ + + + + +
+ +
+ + + +
+ +
+ + + + + +
+ +
+ + + + + + +
+ +
+ + +
+ +
+ +
+ + +
+ + + + + + + + +
+ + +
+ + + + + + + + +
+ +
+ + + + + +
+ +
+ + + + + +
+ +
diff --git a/conf/boards/crazybee_f4_1.0.makefile b/conf/boards/crazybee_f4_1.0.makefile new file mode 100644 index 0000000000..fb1a00aeb1 --- /dev/null +++ b/conf/boards/crazybee_f4_1.0.makefile @@ -0,0 +1,61 @@ +# Hey Emacs, this is a -*- makefile -*- +# +# crazybee_f4_1.0.makefile +# +# Take a look at https://www.openuas.org/ airframes for example + +# Board is a crazybee F4 v1.0 +BOARD=crazybee_f4 +BOARD_VERSION=1.0 +BOARD_CFG=\"boards/crazybee_f4_1.0.h\" + +ARCH=stm32 +ARCH_L=f4 +ARCH_DIR=stm32 +SRC_ARCH=arch/$(ARCH_DIR) +$(TARGET).ARCHDIR = $(ARCH) +$(TARGET).LDSCRIPT=$(SRC_ARCH)/crazybee_f4_1.0.ld + +HARD_FLOAT=yes + +# Default flash mode is the STM32 DFU bootloader +# Theoreticlly possible are also SWD and JTAG_BMP +# But no simple physical connectors to the board... +# So... DFU it will be ... +FLASH_MODE?=DFU-UTIL + +#idVendor=0483, idProduct=5740 +#USB device strings: Mfr=1, Product=2, SerialNumber=3 +#Product: Product: CrazyBee F4 (x) +#Manufacturer: Betaflight +#SerialNumber: 0x8000000 + +#TIP: ttyACM0: USB ACM device + +# +# Default on PCB LED configuration +# +RADIO_CONTROL_LED ?= none +BARO_LED ?= none +AHRS_ALIGNER_LED ?= none +GPS_LED ?= none +SYS_TIME_LED ?= 1 + +# +# Default UART configuration (RC receiver, telemetry modem, GPS) +# +RADIO_CONTROL_SPEKTRUM_PRIMARY_PORT ?= UART2 +RADIO_CONTROL_SBUS_PORT ?= UART2 + +MODEM_PORT ?= UART1 +MODEM_BAUD ?= B115200 + +# +# GPS via I2C just as Baro and Magneto... sparec amount of uart ports left on this board +# If one starts using a build in RX on SPI Bus then TX1/RX1 can be used. +# +# default actuator configuration +# +# you can use different actuators by adding a configure option to your firmware section +# and by setting the correct "driver" attribute in servo section +ACTUATORS ?= actuators_pwm diff --git a/conf/conf_example.xml b/conf/conf_example.xml index 1514ac3f2a..2b82dfbeb0 100644 --- a/conf/conf_example.xml +++ b/conf/conf_example.xml @@ -197,4 +197,15 @@ settings_modules="modules/ahrs_int_cmpl_quat.xml modules/guidance_hybrid.xml modules/stabilization_indi_simple.xml modules/nav_basic_rotorcraft.xml modules/guidance_rotorcraft.xml modules/gps.xml modules/imu_common.xml modules/gps_ubx_ucenter.xml" gui_color="blue" /> + diff --git a/conf/flash_modes.xml b/conf/flash_modes.xml index 82f3de08aa..b1e2b10452 100644 --- a/conf/flash_modes.xml +++ b/conf/flash_modes.xml @@ -61,6 +61,7 @@ + @@ -76,6 +77,7 @@ + diff --git a/conf/modules/dfu_command.xml b/conf/modules/dfu_command.xml new file mode 100644 index 0000000000..d6113f094b --- /dev/null +++ b/conf/modules/dfu_command.xml @@ -0,0 +1,29 @@ + + + + + + THIS MODULE MUST BE PLACED ABOVE ANY USB SERIAL CONSUMERS IN THE AIRFRAME! + + Read USB serial for dfu command. Send '#\n', 'bl\n' to reset to DFU mode. + The same command works with betaflight (tested with 4.1.1), allowing + paparazzi to be uploaded directly to these boards. + + The dfu command is automatically sent when uploading with DFU or DFU-UTIL + (see configure below). + + +
+ +
+ + + + + + + + + +
+ diff --git a/conf/modules/radio_control_cc2500_frsky.xml b/conf/modules/radio_control_cc2500_frsky.xml new file mode 100644 index 0000000000..4965373b6b --- /dev/null +++ b/conf/modules/radio_control_cc2500_frsky.xml @@ -0,0 +1,71 @@ + + + + + + Software implementation of Frsky radio control protocol for onboard CC2500 receiver. + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+ + + +
+ + + + + + + + + + + + + + + + + + + + + + + + + + include $(CFG_SHARED)/spi_master.makefile + + +
diff --git a/conf/modules/telemetry_transparent_frsky_x.xml b/conf/modules/telemetry_transparent_frsky_x.xml new file mode 100644 index 0000000000..e6da71383b --- /dev/null +++ b/conf/modules/telemetry_transparent_frsky_x.xml @@ -0,0 +1,66 @@ + + + + + + Telemetry using pprzlink protocol over FrSky X SmartPort serial link + + Downlink messages are sent on dataID 0x5015. + Uplink is not implemented yet. + + Use the sw/tools/opentx-lua/sp2ser.lua script to receive these messages + on the TX and forward them to the USB port. The 'datalink' script can + read the pprzlink stream as a regular serial port. + + The data rate is very limited (max ~160 bytes/s). The limitation comes + from the FrSky X protocol which can send at most 4 bytes of telemetry + every 9ms. Set CC2500_TELEMETRY_SENSORS (from radio_control_cc2500_frsky) + to SENSOR_NONE to maximize pprzlink throughput. Use a suitable telemetry + conf for this low data rate. + + + + +
+ + +
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+ diff --git a/conf/radios/FrSky_Taranis_X9Dplus_TAERMK.xml b/conf/radios/FrSky_Taranis_X9Dplus_TAERMK.xml new file mode 100644 index 0000000000..05aca8d6b6 --- /dev/null +++ b/conf/radios/FrSky_Taranis_X9Dplus_TAERMK.xml @@ -0,0 +1,10 @@ + + + + + + + + + + diff --git a/sw/airborne/arch/stm32/crazybee_f4_1.0.ld b/sw/airborne/arch/stm32/crazybee_f4_1.0.ld new file mode 100644 index 0000000000..ff1bd7d8f1 --- /dev/null +++ b/sw/airborne/arch/stm32/crazybee_f4_1.0.ld @@ -0,0 +1,38 @@ +/* + * Hey Emacs, this is a -*- makefile -*- + * + * Copyright (C) 2019 PPRZ team + * + * This file is part of Paparazzi. + * + * Paparazzi 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 2, or (at your option) + * any later version. + * + * Paparazzi 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 Paparazzi; see the file COPYING. If not, write to + * the Free Software Foundation, 59 Temple Place - Suite 330, + * Boston, MA 02111-1307, USA. + */ + +/* Linker script for Crazybee F4 (STM32F411CEU6), 512K FLASH flash, 128K RAM). */ + +/* FIXME: values possibly not correct +/* Define memory regions. */ +MEMORY +{ + ram (rwx) : ORIGIN = 0x20000000, LENGTH = 128K + /* Reserving 16kb flash (512-16=496) for persistent settings. */ + rom (rx) : ORIGIN = 0x08000000, LENGTH = 496K + +} + +/* Include the common ld script. */ +INCLUDE libopencm3_stm32f4.ld +/* INCLUDE cortex-m-generic.ld */ diff --git a/sw/airborne/arch/stm32/mcu_arch.c b/sw/airborne/arch/stm32/mcu_arch.c index 8915c3d480..0fa9b3f9f3 100644 --- a/sw/airborne/arch/stm32/mcu_arch.c +++ b/sw/airborne/arch/stm32/mcu_arch.c @@ -36,6 +36,8 @@ #include #include #include +#include +#include #include "std.h" @@ -165,8 +167,55 @@ void rcc_clock_setup_in_hse_24mhz_out_24mhz_pprz(void) } #endif + +#ifdef SYSTEM_MEMORY_BASE +void reset_to_dfu(void) { + // Request DFU at boot (init_dfu) + pwr_disable_backup_domain_write_protect(); + RTC_BKPXR(0) = 0xFF; + pwr_enable_backup_domain_write_protect(); + // Reset + scb_reset_system(); +} + +typedef void resetHandler_t(void); + +typedef struct isrVector_s { + volatile uint32_t stackEnd; + resetHandler_t *resetHandler; +} isrVector_t; + +static isrVector_t *system_isr_vector_table_base = (isrVector_t *) SYSTEM_MEMORY_BASE; // Find in ST AN2606. Defined in board header. + +static void init_dfu(void) { + /* Reset to DFU if requested */ + rcc_periph_clock_enable(RCC_RTC); + rcc_periph_clock_enable(RCC_PWR); + if (RTC_BKPXR(0) == 0xFF) { + // DFU request + // 0. Reset request + pwr_disable_backup_domain_write_protect(); + RTC_BKPXR(0) = 0x00; + pwr_enable_backup_domain_write_protect(); + // 1. Set MSP to system_isr_vector_table_base.stackEnd + // (betaflight system_stm32f4xx.c::75) + // (betaflight cmsis_armcc.h::226 + register uint32_t __regMainStackPointer __asm("msp") __attribute__((unused)); // Note: declared unused to suppress gcc warning, not actually unused! + __regMainStackPointer = system_isr_vector_table_base->stackEnd; // = topOfMainStack; + // 2. system_isr_vector_table_base.resetHandler() (betaflight system_stm32f4xx.c::76) + system_isr_vector_table_base->resetHandler(); + while (1); + } +} +#endif // SYSTEM_MEMORY_BASE + + void mcu_arch_init(void) { +#ifdef SYSTEM_MEMORY_BASE + init_dfu(); +#endif + #if LUFTBOOT PRINT_CONFIG_MSG("We are running luftboot, the interrupt vector is being relocated.") #if defined STM32F4 @@ -222,7 +271,6 @@ void mcu_arch_init(void) * FIXME is it really needed ? */ scb_set_priority_grouping(SCB_AIRCR_PRIGROUP_NOGROUP_SUB16); - } #if defined(STM32F1) diff --git a/sw/airborne/arch/stm32/mcu_arch.h b/sw/airborne/arch/stm32/mcu_arch.h index 02b9a83607..9e9740f407 100644 --- a/sw/airborne/arch/stm32/mcu_arch.h +++ b/sw/airborne/arch/stm32/mcu_arch.h @@ -31,8 +31,14 @@ #include "std.h" +#include BOARD_CONFIG + extern void mcu_arch_init(void); +#ifdef SYSTEM_MEMORY_BASE +extern void reset_to_dfu(void); +#endif + /* should probably not be here * a couple of macros to use the rev instruction diff --git a/sw/airborne/arch/stm32/usb_ser_hw.c b/sw/airborne/arch/stm32/usb_ser_hw.c index e3a53694c0..78b89a3fd9 100644 --- a/sw/airborne/arch/stm32/usb_ser_hw.c +++ b/sw/airborne/arch/stm32/usb_ser_hw.c @@ -64,6 +64,7 @@ static fifo_t rxfifo; void fifo_init(fifo_t *fifo, uint8_t *buf); bool fifo_put(fifo_t *fifo, uint8_t c); bool fifo_get(fifo_t *fifo, uint8_t *pc); +bool fifo_peek(fifo_t *fifo, uint8_t *pc, uint8_t ofs); int fifo_avail(fifo_t *fifo); int fifo_free(fifo_t *fifo); int tx_timeout; // tmp work around for usbd_ep_stall_get from, this function does not always seem to work @@ -374,6 +375,15 @@ int fifo_free(fifo_t *fifo) return (VCOM_FIFO_SIZE - 1 - fifo_avail(fifo)); } +bool fifo_peek(fifo_t *fifo, uint8_t *pc, uint8_t ofs) { + if (fifo_avail(fifo) < ofs + 1) { + return false; + } + int index = (fifo->tail + ofs) % VCOM_FIFO_SIZE; + *pc = fifo->buf[index]; + return true; +} + /** * Writes one character to VCOM port fifo. @@ -420,6 +430,19 @@ int VCOM_getchar(void) return result; } +/** + * Reads one character from VCOM port without removing it from the queue + * @param ofs position to read + * @returns character read, or -1 if character could not be read + */ +int VCOM_peekchar(int ofs) +{ + static int result = 0; + uint8_t c; + result = fifo_peek(&rxfifo, &c, ofs) ? c : -1; + return result; +} + /** * Checks if buffer free in VCOM buffer * @returns TRUE if len bytes are free diff --git a/sw/airborne/boards/crazybee_f4_1.0.h b/sw/airborne/boards/crazybee_f4_1.0.h new file mode 100644 index 0000000000..8e0c43525f --- /dev/null +++ b/sw/airborne/boards/crazybee_f4_1.0.h @@ -0,0 +1,309 @@ +/* Since there is atm no schematic of the board, many pin to pin io was deducted + * by measuring on the PCB. + * Not all, e.g. the Volt and Current values are measured for the moment + * Would be great if one could determine the resitor bridge true values + */ + +#ifndef CONFIG_CRAZYBEE_F4_1_0_H +#define CONFIG_CRAZYBEE_F4_1_0_H + +#define BOARD_CRAZYBEE_F4_V1 + +/** System memory base - for DFU bootloader */ +#define SYSTEM_MEMORY_BASE 0x1FFF0000 + +/** Clock config - STM32F4 - STM32F411CEU6 in 48 pin package UFQFPN48 **/ +#define EXT_CLK 8000000 // 8mHz +#define AHB_CLK 84000000 + +/** LEDs **/ +/* Green LED on flight controller */ +#ifndef USE_LED_1 +#define USE_LED_1 1 +#endif +#define LED_1_GPIO GPIOC +#define LED_1_GPIO_PIN GPIO13 +#define LED_1_GPIO_ON gpio_clear +#define LED_1_GPIO_OFF gpio_set +#define LED_1_AFIO_REMAP ((void)0) + +/* Red/white RX LEDs */ +/* Note: all LEDs are connected to a single pin */ +#ifndef USE_LED_2 +#define USE_LED_2 1 +#endif +#define LED_2_GPIO GPIOB +#define LED_2_GPIO_PIN GPIO9 +#define LED_2_GPIO_ON gpio_set +#define LED_2_GPIO_OFF gpio_clear +#define LED_2_AFIO_REMAP ((void)0) + +/** UART's **/ +/* UART1 */ +#define UART1_GPIO_AF GPIO_AF7 +#define UART1_GPIO_PORT_TX GPIOA +#define UART1_GPIO_TX GPIO9 +#define UART1_GPIO_PORT_RX GPIOA +#define UART1_GPIO_RX GPIO10 + +/* UART2 */ +//Can connect to built-in DSMX receiver is availabe on UART RX +//Not to be confused with DSMX over SPI, that is unrelated +#define UART2_GPIO_AF GPIO_AF7 +#define UART2_GPIO_PORT_TX GPIOA +#define UART2_GPIO_TX GPIO2 +#define UART2_GPIO_PORT_RX GPIOA +#define UART2_GPIO_RX GPIO3 + +/* SBUS inverted on UARTx is a separate physical pad on the board + * To be used for an receiverv that gives an inverted SBUS out signal */ + +/* FIXME: (re)setting UART based (e.g. Spektum) Serial RADIO_CONTROL_POWER_PORT +#define RADIO_CONTROL_POWER_PORT GPIOA +#define RADIO_CONTROL_POWER_PIN GPIO10 +#define RADIO_CONTROL_POWER_ON gpio_clear // yes, inverted +#define RADIO_CONTROL_POWER_OFF gpio_set +*/ + +/* FIXME: Soft binding Spektrum */ +/* +#define SPEKTRUM_UART2_RCC RCC_USART1 //But uard 2 if embedded CYRF chip Speksat can be on UART1 +#define SPEKTRUM_UART2_BANK GPIOA +#define SPEKTRUM_UART2_PIN GPIO10 +#define SPEKTRUM_UART2_AF GPIO_AF7 +#define SPEKTRUM_UART2_IRQ NVIC_USART1_IRQ +#define SPEKTRUM_UART2_ISR usart1_isr +#define SPEKTRUM_UART2_DEV USART1 +*/ + +/* FIXME to relate this to ifddefs of PPM config possibilities + */ +#ifndef USE_LED_STRIP +#define USE_LED_STRIP 1 +#endif + +#if USE_LED_STRIP +#define LED_STRIP_GPIO_PORT GPIOA +#define LED_STRIP_GPIO_PIN GPIO0 +#endif + +/* PPM + * + * FIXME: Default is PPM config 1, alternative 2 is CPPM input on RX2 pin but + * than no UART RX at the same time, but a need for that scenario is unlikely anyhow + * + * Originaly intended for 2812LED board - DMA1_ST2 + * Can be re- used for input to connect a receiver that outputs CPPM pulsestrain + */ + +#ifndef PPM_CONFIG +#define PPM_CONFIG 1 +#endif + +#ifdef PPM_CONFIG +#define USE_PPM_TIM5 1 +#define PPM_CHANNEL TIM_IC1 +#define PPM_TIMER_INPUT TIM_IC_IN_TI1 +#define PPM_IRQ NVIC_TIM5_IRQ +//#define PPM_IRQ NVIC_TIM5_CC_IRQ +// Capture/Compare InteruptEnable and InterruptFlag +#define PPM_CC_IE TIM_DIER_CC1IE +#define PPM_CC_IF TIM_SR_CC1IF +#define PPM_GPIO_PORT GPIOA +#define PPM_GPIO_PIN GPIO0 +#define PPM_GPIO_AF GPIO_AF2 + +//#elif PPM_CONFIG == 2 +///* RX SBUS/Spektumserial or CPPM input on PA3 (RX2 pin) */ +//#define USE_PPM_TIM9 1 +//#define PPM_CHANNEL TIM_IC2 +//#define PPM_TIMER_INPUT TIM_IC_IN_TI2 +//#define PPM_IRQ NVIC_TIM9_IRQ +//// Capture/Compare InteruptEnable and InterruptFlag +//#define PPM_CC_IE TIM_DIER_CC2IE +//#define PPM_CC_IF TIM_SR_CC2IF +//#define PPM_GPIO_PORT GPIOA +//#define PPM_GPIO_PIN GPIO3 +//#define PPM_GPIO_AF GPIO_AF3 +///* TODO: add option 3 of input on RX1 pin) */ +//#else +//#error "Unknown PPM config" + +#endif // PPM_CONFIG + +/** SPI **/ +/* SPI1 for MPU accel/gyro (MPU6000*/ +#define SPI1_GPIO_AF GPIO_AF5 +#define SPI1_GPIO_PORT_SCK GPIOA +#define SPI1_GPIO_SCK GPIO5 +#define SPI1_GPIO_PORT_MISO GPIOA +#define SPI1_GPIO_MISO GPIO6 +#define SPI1_GPIO_PORT_MOSI GPIOA +#define SPI1_GPIO_MOSI GPIO7 + +/* SPI slave pin declaration ACC_GYRO_CS on SPI1 ICM 20609-G*/ +#define SPI_SELECT_SLAVE0_PORT GPIOA +#define SPI_SELECT_SLAVE0_PIN GPIO4 + +/* SPI2 for embedded OSD MAX chip*/ +//#ifndef USE_MAX7456 +//#define USE_MAX7456 0 +//#endif + +//#if USE_MAX7456 +#define SPI2_GPIO_AF GPIO_AF5 //TODO check datasheet +#define SPI2_GPIO_PORT_SCK GPIOB +#define SPI2_GPIO_SCK GPIO13 +#define SPI2_GPIO_PORT_MISO GPIOB +#define SPI2_GPIO_MISO GPIO14 +#define SPI2_GPIO_PORT_MOSI GPIOB +#define SPI2_GPIO_MOSI GPIO15 + +/* SPI slave pin declaration OSD */ +#define SPI_SELECT_SLAVE1_PORT GPIOB +#define SPI_SELECT_SLAVE1_PIN GPIO12 +//#endif + +/* Used SPI3 for RX direct, if RX solution is implemented in AP */ +#define SPI3_GPIO_AF GPIO_AF6 +#define SPI3_GPIO_PORT_SCK GPIOB +#define SPI3_GPIO_SCK GPIO3 +#define SPI3_GPIO_PORT_MISO GPIOB +#define SPI3_GPIO_MISO GPIO4 +#define SPI3_GPIO_PORT_MOSI GPIOB +#define SPI3_GPIO_MOSI GPIO5 + +/* SPI slave pin declaration for Receiver */ +#define SPI_SELECT_SLAVE2_PORT GPIOA +#define SPI_SELECT_SLAVE2_PIN GPIO15 + +/* GDO0 pin for receiver */ +#define CC2500_GDO0_GPIO GPIOC +#define CC2500_GDO0_PIN GPIO14 + +/* Bind button */ +#define BIND_BUTTON_GPIO GPIOB +#define BIND_BUTTON_PIN GPIO2 + +/** Onboard ADCs **/ + +#define USE_AD_TIM1 1 + +/* Voltage */ +#ifndef USE_ADC_1 +#define USE_ADC_1 1 +#endif + +#if USE_ADC_1 +#define AD1_1_CHANNEL 8 +#define ADC_1 AD1_1 +#define ADC_1_GPIO_PORT GPIOB +#define ADC_1_GPIO_PIN GPIO0 + +#define ADC_CHANNEL_VSUPPLY ADC_1 +#define DefaultVoltageOfAdc(adc) (0.009*adc)// TODO: determine 100% correct value +#endif + +/* Current */ +#ifndef USE_ADC_2 +#define USE_ADC_2 1 +#endif + +#if USE_ADC_2 +#define AD1_2_CHANNEL 9 +#define ADC_2 AD1_2 +#define ADC_2_GPIO_PORT GPIOB +#define ADC_2_GPIO_PIN GPIO1 + +#define ADC_CHANNEL_CURRENT ADC_2 +#define MilliAmpereOfAdc(adc)((float)adc) * (3.3f / 4096.0f) * (90.0f / 5.0f)// TODO: determine 100% correct value +#endif + +/* TODO: Somehere on the board find PHiSICAL easily reachable I2C SDL SDA so to connect e.g. GNSS, Baro, Magneto + * TODO: Finish the I2C mapping if Pins found */ + +//#define I2C1_GPIO_AF GPIO_AF4 +//#define I2C1_GPIO_PORT GPIOB +//#define I2C1_GPIO_SCL GPIO8 +//#define I2C1_GPIO_SDA GPIO9 + +/* Default actuators driver */ +#define DEFAULT_ACTUATORS "subsystems/actuators/actuators_pwm.h" +#define ActuatorDefaultSet(_x,_y) ActuatorPwmSet(_x,_y) +#define ActuatorsDefaultInit() ActuatorsPwmInit() +#define ActuatorsDefaultCommit() ActuatorsPwmCommit() + +/* PWM */ +#define PWM_USE_TIM2 1 +#define PWM_USE_TIM4 1 + +#define USE_PWM1 1 +#define USE_PWM2 1 +#define USE_PWM3 1 +#define USE_PWM4 1 + +/* ESC 1 (B10, TIM2, CH3)*/ +#if USE_PWM1 +#define PWM_SERVO_1 0 +#define PWM_SERVO_1_TIMER TIM2 +#define PWM_SERVO_1_GPIO GPIOB +#define PWM_SERVO_1_PIN GPIO10 +#define PWM_SERVO_1_AF GPIO_AF1 +#define PWM_SERVO_1_OC TIM_OC3 +#define PWM_SERVO_1_OC_BIT (1<<2) +#else +#define PWM_SERVO_1_OC_BIT 0 +#endif + +/* ESC 2 (B6, TIM4, CH1)*/ +#if USE_PWM2 +#define PWM_SERVO_2 1 +#define PWM_SERVO_2_TIMER TIM4 +#define PWM_SERVO_2_GPIO GPIOB +#define PWM_SERVO_2_PIN GPIO6 +#define PWM_SERVO_2_AF GPIO_AF2 +#define PWM_SERVO_2_OC TIM_OC1 +#define PWM_SERVO_2_OC_BIT (1<<0) +#else +#define PWM_SERVO_2_OC_BIT 0 +#endif + +/* ESC 3 (B7, TIM4, CH2) */ +#if USE_PWM3 +#define PWM_SERVO_3 2 +#define PWM_SERVO_3_TIMER TIM4 +#define PWM_SERVO_3_GPIO GPIOB +#define PWM_SERVO_3_PIN GPIO7 +#define PWM_SERVO_3_AF GPIO_AF2 +#define PWM_SERVO_3_OC TIM_OC2 +#define PWM_SERVO_3_OC_BIT (1<<1) +#else +#define PWM_SERVO_3_OC_BIT 0 +#endif + +/* ESC 4 (B8, TIM4, CH3) */ +#if USE_PWM4 +#define PWM_SERVO_4 3 +#define PWM_SERVO_4_TIMER TIM4 +#define PWM_SERVO_4_GPIO GPIOB +#define PWM_SERVO_4_PIN GPIO8 +#define PWM_SERVO_4_AF GPIO_AF2 +#define PWM_SERVO_4_OC TIM_OC3 +#define PWM_SERVO_4_OC_BIT (1<<2) +#else +#define PWM_SERVO_4_OC_BIT 0 +#endif + +#define PWM_TIM2_CHAN_MASK (PWM_SERVO_1_OC_BIT) +#define PWM_TIM4_CHAN_MASK (PWM_SERVO_2_OC_BIT|PWM_SERVO_3_OC_BIT|PWM_SERVO_4_OC_BIT) + +/* Buzzer (C15, inverted) */ +#if USE_BUZZER +#define PWM_BUZZER +#define PWM_BUZZER_GPIO GPIOC +#define PWM_BUZZER_PIN GPI15 +#define PWM_BUZZER_GPIO_ON gpio_clear +#define PWM_BUZZER_GPIO_OFF gpio_set +#endif + +#endif /* CONFIG_CRAZYBEE_F4_1_0_H */ diff --git a/sw/airborne/mcu_periph/usb_serial.h b/sw/airborne/mcu_periph/usb_serial.h index 928882dd9d..337f5a9312 100644 --- a/sw/airborne/mcu_periph/usb_serial.h +++ b/sw/airborne/mcu_periph/usb_serial.h @@ -42,6 +42,7 @@ extern struct usb_serial_periph usb_serial; void VCOM_init(void); int VCOM_putchar(int c); int VCOM_getchar(void); +int VCOM_peekchar(int ofs); bool VCOM_check_free_space(uint16_t len); int VCOM_check_available(void); void VCOM_set_linecoding(uint8_t mode); diff --git a/sw/airborne/modules/datalink/pprz_dl.h b/sw/airborne/modules/datalink/pprz_dl.h index d052c693c7..94c74d0ce8 100644 --- a/sw/airborne/modules/datalink/pprz_dl.h +++ b/sw/airborne/modules/datalink/pprz_dl.h @@ -32,6 +32,9 @@ #if USE_USB_SERIAL #include "mcu_periph/usb_serial.h" #endif +#if USE_FRSKY_X_SERIAL +#include "subsystems/datalink/frsky_x.h" +#endif #if USE_UDP #include "mcu_periph/udp.h" #endif diff --git a/sw/airborne/modules/dfu_command/dfu_command.c b/sw/airborne/modules/dfu_command/dfu_command.c new file mode 100644 index 0000000000..d937fb8e4d --- /dev/null +++ b/sw/airborne/modules/dfu_command/dfu_command.c @@ -0,0 +1,57 @@ +/* + * Copyright (C) Tom van Dijk + * + * This file is part of paparazzi + * + * paparazzi 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 2, or (at your option) + * any later version. + * + * paparazzi 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 paparazzi; see the file COPYING. If not, see + * . + */ +/** + * @file "modules/dfu_command/dfu_command.c" + * @author Tom van Dijk + * Read USB serial for dfu command + * + * The reset_to_dfu() function needs to be implemented for the + * architecture in use. (sw/airborne/arch/.../mcu_arch.c) + */ + +#include "modules/dfu_command/dfu_command.h" + +#include "mcu_arch.h" + +static const char dfu_command_str[] = "#\nbl\n"; // Note: same command resets betaflight to DFU +static int dfu_command_state = 0; + +void dfu_command_event(void) { + // Search fifo for command string + for (int i = 0; i < VCOM_check_available(); ++i) { + if (VCOM_peekchar(i) == dfu_command_str[dfu_command_state]) { + dfu_command_state++; + if (dfu_command_str[dfu_command_state] == '\0') { // end of command string + reset_to_dfu(); + } + } else { + dfu_command_state = 0; + } + } + + // Prevent fifo blocking if bytes are not consumed by other process + if (!VCOM_check_free_space(1)) { + while (VCOM_check_available()) { + VCOM_getchar(); + } + } +} + + diff --git a/sw/airborne/modules/dfu_command/dfu_command.h b/sw/airborne/modules/dfu_command/dfu_command.h new file mode 100644 index 0000000000..e70e7094ab --- /dev/null +++ b/sw/airborne/modules/dfu_command/dfu_command.h @@ -0,0 +1,34 @@ +/* + * Copyright (C) Tom van Dijk + * + * This file is part of paparazzi + * + * paparazzi 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 2, or (at your option) + * any later version. + * + * paparazzi 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 paparazzi; see the file COPYING. If not, see + * . + */ +/** + * @file "modules/dfu_command/dfu_command.h" + * @author Tom van Dijk + * Read USB serial for dfu command + */ + +#ifndef DFU_COMMAND_H +#define DFU_COMMAND_H + +#include "mcu_periph/usb_serial.h" + +void dfu_command_event(void); + +#endif + diff --git a/sw/airborne/peripherals/cc2500.c b/sw/airborne/peripherals/cc2500.c new file mode 100644 index 0000000000..d45a5f8d7d --- /dev/null +++ b/sw/airborne/peripherals/cc2500.c @@ -0,0 +1,237 @@ +/* + * Copyright (C) 2019 Tom van Dijk + * + * This code is based on the betaflight cc2500 and FrskyX implementation. + * https://github.com/betaflight/betaflight + * + * This file is part of paparazzi. + * + * paparazzi 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 2, or (at your option) + * any later version. + * + * paparazzi 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 paparazzi; see the file COPYING. If not, write to + * the Free Software Foundation, 59 Temple Place - Suite 330, + * Boston, MA 02111-1307, USA. + */ + +#include "subsystems/datalink/downlink.h" // TODO remove before PR + +#include "cc2500.h" + +#include "generated/modules.h" +#include "mcu_periph/sys_time.h" +#include "mcu_periph/spi.h" + +#include + +#define USE_RX_CC2500 + +static struct spi_periph *cc2500_spi_p; +static struct spi_transaction cc2500_spi_t; +static uint8_t cc2500_input_buf[64]; +static uint8_t cc2500_output_buf[64]; + + +void cc2500_init(void) { + /* Set spi peripheral */ + cc2500_spi_p = &(CC2500_SPI_DEV); + /* Set the spi transaction */ + cc2500_spi_t.input_buf = cc2500_input_buf; + cc2500_spi_t.output_buf = cc2500_output_buf; + cc2500_spi_t.input_length = 0; + cc2500_spi_t.output_length = 0; + cc2500_spi_t.select = SPISelectUnselect; + cc2500_spi_t.cpol = SPICpolIdleLow; + cc2500_spi_t.cpha = SPICphaEdge1; + cc2500_spi_t.dss = SPIDss8bit; + cc2500_spi_t.bitorder = SPIMSBFirst; + cc2500_spi_t.cdiv = SPIDiv32; // Found experimentally + cc2500_spi_t.status = SPITransDone; + cc2500_spi_t.slave_idx = CC2500_SPI_SLAVE_IDX; +} + + +static void cc2500_delayMicroseconds(uint32_t us) { + float start = get_sys_time_float(); + while(get_sys_time_float() < start + (us / 1.0e6)) ; +} +// Fix naming conflict with subsystems/radio_control/cc2500_frsky delayMicroseconds +#ifdef delayMicroseconds +#undef delayMicroseconds +#endif +#define delayMicroseconds(us) cc2500_delayMicroseconds(us) + + +static void rxSpiReadCommandMulti(uint8_t command, uint8_t commandData, uint8_t *retData, uint8_t length) { + // Check that the SPI transaction is not busy + assert(cc2500_spi_t.status == SPITransDone); + // Set up the transaction + cc2500_spi_t.output_length = 2; // command + commandData + cc2500_spi_t.input_length = length + 1; // STATUS BYTE + RETURN DATA + cc2500_spi_t.output_buf[0] = command; + cc2500_spi_t.output_buf[1] = commandData; + // Submit the transaction + spi_submit(cc2500_spi_p, &cc2500_spi_t); + // Spin until transaction is completed + while(cc2500_spi_t.status != SPITransSuccess) ; // TODO not ideal in event function... + cc2500_spi_t.status = SPITransDone; + // Copy the input buffer + for (uint8_t i = 0; i < length; ++i) { + retData[i] = cc2500_spi_t.input_buf[i + 1]; // Skips status byte, betaflight code does not work when this byte is included. + } +} + +static uint8_t rxSpiReadCommand(uint8_t command, uint8_t commandData) { + uint8_t retData; // DATA + rxSpiReadCommandMulti(command, commandData, &retData, 1); + return retData; +} + + +static void rxSpiWriteCommandMulti(uint8_t command, uint8_t *data, uint8_t length) { + // Check that the SPI transaction is not busy + assert(cc2500_spi_t.status == SPITransDone); + // Set up the transaction + cc2500_spi_t.output_length = length + 1; // command + data[length] + cc2500_spi_t.input_length = 0; + cc2500_spi_t.output_buf[0] = command; + // Copy the data to the output buffer + for (uint8_t i = 0; i < length; ++i) { + cc2500_spi_t.output_buf[i + 1] = data[i]; + } + // Submit the transaction + spi_submit(cc2500_spi_p, &cc2500_spi_t); + // Spin until transaction is completed + while(cc2500_spi_t.status != SPITransSuccess) ; // TODO not ideal in event function... + cc2500_spi_t.status = SPITransDone; +} + +static void rxSpiWriteCommand(uint8_t command, uint8_t data) { + rxSpiWriteCommandMulti(command, &data, 1); +} + +static void rxSpiWriteByte(uint8_t data) { + rxSpiWriteCommandMulti(data, NULL, 0); +} + + + +// betaflight/src/main/drivers/rx/rx_cc2500.c @ 0a16f4d on Oct 1, 2018 + +/* + * This file is part of Cleanflight and Betaflight. + * + * Cleanflight and Betaflight are free software. You can redistribute + * this software and/or modify this software under the terms of the + * GNU General Public License as published by the Free Software + * Foundation, either version 3 of the License, or (at your option) + * any later version. + * + * Cleanflight and Betaflight are distributed in the hope that they + * will be useful, but WITHOUT ANY WARRANTY; without even the implied + * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + * See the GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this software. + * + * If not, see . + */ + +/* +* CC2500 SPI drivers +*/ +#include +#include +#include + +//#include "platform.h" + +#ifdef USE_RX_CC2500 + +//#include "build/build_config.h" +// +//#include "pg/rx.h" +//#include "pg/rx_spi.h" +// +//#include "drivers/io.h" +//#include "drivers/rx/rx_spi.h" +//#include "drivers/system.h" +//#include "drivers/time.h" + +//#include "rx_cc2500.h" + +#define NOP 0xFF + +void cc2500ReadFifo(uint8_t *dpbuffer, uint8_t len) +{ + rxSpiReadCommandMulti(CC2500_3F_RXFIFO | CC2500_READ_BURST, NOP, dpbuffer, len); +// DOWNLINK_SEND_CC2500_PACKET(DefaultChannel, DefaultDevice,len, dpbuffer); +} + +void cc2500WriteFifo(uint8_t *dpbuffer, uint8_t len) +{ + cc2500Strobe(CC2500_SFTX); // 0x3B SFTX + rxSpiWriteCommandMulti(CC2500_3F_TXFIFO | CC2500_WRITE_BURST, + dpbuffer, len); + cc2500Strobe(CC2500_STX); // 0x35 +} + +void cc2500ReadRegisterMulti(uint8_t address, uint8_t *data, uint8_t length) +{ + rxSpiReadCommandMulti(address, NOP, data, length); +} + +void cc2500WriteRegisterMulti(uint8_t address, uint8_t *data, + uint8_t length) +{ + rxSpiWriteCommandMulti(address, data, length); +} + +uint8_t cc2500ReadReg(uint8_t reg) +{ + return rxSpiReadCommand(reg | 0x80, NOP); +} + +void cc2500Strobe(uint8_t address) { rxSpiWriteByte(address); } + +void cc2500WriteReg(uint8_t address, uint8_t data) +{ + rxSpiWriteCommand(address, data); +} + +void cc2500SetPower(uint8_t power) +{ + const uint8_t patable[8] = { + 0xC5, // -12dbm + 0x97, // -10dbm + 0x6E, // -8dbm + 0x7F, // -6dbm + 0xA9, // -4dbm + 0xBB, // -2dbm + 0xFE, // 0dbm + 0xFF // 1.5dbm + }; + if (power > 7) + power = 7; + cc2500WriteReg(CC2500_3E_PATABLE, patable[power]); +} + +uint8_t cc2500Reset(void) +{ + cc2500Strobe(CC2500_SRES); + delayMicroseconds(1000); // 1000us + // CC2500_SetTxRxMode(TXRX_OFF); + // RX_EN_off;//off tx + // TX_EN_off;//off rx + return cc2500ReadReg(CC2500_0E_FREQ1) == 0xC4; // check if reset +} +#endif diff --git a/sw/airborne/peripherals/cc2500.h b/sw/airborne/peripherals/cc2500.h new file mode 100644 index 0000000000..c53914e336 --- /dev/null +++ b/sw/airborne/peripherals/cc2500.h @@ -0,0 +1,207 @@ +/* + * Copyright (C) 2019 Tom van Dijk + * + * This code is based on the betaflight cc2500 and FrskyX implementation. + * https://github.com/betaflight/betaflight + * + * This file is part of paparazzi. + * + * paparazzi 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 2, or (at your option) + * any later version. + * + * paparazzi 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 paparazzi; see the file COPYING. If not, write to + * the Free Software Foundation, 59 Temple Place - Suite 330, + * Boston, MA 02111-1307, USA. + */ + +#ifndef PERIPHERALS_CC2500_H +#define PERIPHERALS_CC2500_H + +void cc2500_init(void); + + +// betaflight/src/main/drivers/rx/rx_cc2500.h @ 0a16f4d on Oct 1, 2018 + +/* + * This file is part of Cleanflight and Betaflight. + * + * Cleanflight and Betaflight are free software. You can redistribute + * this software and/or modify this software under the terms of the + * GNU General Public License as published by the Free Software + * Foundation, either version 3 of the License, or (at your option) + * any later version. + * + * Cleanflight and Betaflight are distributed in the hope that they + * will be useful, but WITHOUT ANY WARRANTY; without even the implied + * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + * See the GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this software. + * + * If not, see . + */ + +/* + CC2500 SPI drivers +*/ + +#pragma once + +#include +#include + +//#include "rx/rx_spi.h" + +enum { + CC2500_00_IOCFG2 = 0x00, // GDO2 output pin configuration + CC2500_01_IOCFG1 = 0x01, // GDO1 output pin configuration + CC2500_02_IOCFG0 = 0x02, // GDO0 output pin configuration + CC2500_03_FIFOTHR = 0x03, // RX FIFO and TX FIFO thresholds + CC2500_04_SYNC1 = 0x04, // Sync word, high byte + CC2500_05_SYNC0 = 0x05, // Sync word, low byte + CC2500_06_PKTLEN = 0x06, // Packet length + CC2500_07_PKTCTRL1 = 0x07, // Packet automation control + CC2500_08_PKTCTRL0 = 0x08, // Packet automation control + CC2500_09_ADDR = 0x09, // Device address + CC2500_0A_CHANNR = 0x0A, // Channel number + CC2500_0B_FSCTRL1 = 0x0B, // Frequency synthesizer control + CC2500_0C_FSCTRL0 = 0x0C, // Frequency synthesizer control + CC2500_0D_FREQ2 = 0x0D, // Frequency control word, high byte + CC2500_0E_FREQ1 = 0x0E, // Frequency control word, middle byte + CC2500_0F_FREQ0 = 0x0F, // Frequency control word, low byte + CC2500_10_MDMCFG4 = 0x10, // Modem configuration + CC2500_11_MDMCFG3 = 0x11, // Modem configuration + CC2500_12_MDMCFG2 = 0x12, // Modem configuration + CC2500_13_MDMCFG1 = 0x13, // Modem configuration + CC2500_14_MDMCFG0 = 0x14, // Modem configuration + CC2500_15_DEVIATN = 0x15, // Modem deviation setting + CC2500_16_MCSM2 = 0x16, // Main Radio Cntrl State Machine config + CC2500_17_MCSM1 = 0x17, // Main Radio Cntrl State Machine config + CC2500_18_MCSM0 = 0x18, // Main Radio Cntrl State Machine config + CC2500_19_FOCCFG = 0x19, // Frequency Offset Compensation config + CC2500_1A_BSCFG = 0x1A, // Bit Synchronization configuration + CC2500_1B_AGCCTRL2 = 0x1B, // AGC control + CC2500_1C_AGCCTRL1 = 0x1C, // AGC control + CC2500_1D_AGCCTRL0 = 0x1D, // AGC control + CC2500_1E_WOREVT1 = 0x1E, // High byte Event 0 timeout + CC2500_1F_WOREVT0 = 0x1F, // Low byte Event 0 timeout + CC2500_20_WORCTRL = 0x20, // Wake On Radio control + CC2500_21_FREND1 = 0x21, // Front end RX configuration + CC2500_22_FREND0 = 0x22, // Front end TX configuration + CC2500_23_FSCAL3 = 0x23, // Frequency synthesizer calibration + CC2500_24_FSCAL2 = 0x24, // Frequency synthesizer calibration + CC2500_25_FSCAL1 = 0x25, // Frequency synthesizer calibration + CC2500_26_FSCAL0 = 0x26, // Frequency synthesizer calibration + CC2500_27_RCCTRL1 = 0x27, // RC oscillator configuration + CC2500_28_RCCTRL0 = 0x28, // RC oscillator configuration + CC2500_29_FSTEST = 0x29, // Frequency synthesizer cal control + CC2500_2A_PTEST = 0x2A, // Production test + CC2500_2B_AGCTEST = 0x2B, // AGC test + CC2500_2C_TEST2 = 0x2C, // Various test settings + CC2500_2D_TEST1 = 0x2D, // Various test settings + CC2500_2E_TEST0 = 0x2E, // Various test settings + + // Status registers + CC2500_30_PARTNUM = 0x30, // Part number + CC2500_31_VERSION = 0x31, // Current version number + CC2500_32_FREQEST = 0x32, // Frequency offset estimate + CC2500_33_LQI = 0x33, // Demodulator estimate for link quality + CC2500_34_RSSI = 0x34, // Received signal strength indication + CC2500_35_MARCSTATE = 0x35, // Control state machine state + CC2500_36_WORTIME1 = 0x36, // High byte of WOR timer + CC2500_37_WORTIME0 = 0x37, // Low byte of WOR timer + CC2500_38_PKTSTATUS = 0x38, // Current GDOx status and packet status + CC2500_39_VCO_VC_DAC = 0x39, // Current setting from PLL cal module + CC2500_3A_TXBYTES = 0x3A, // Underflow and # of bytes in TXFIFO + CC2500_3B_RXBYTES = 0x3B, // Overflow and # of bytes in RXFIFO + + // Multi byte memory locations + CC2500_3E_PATABLE = 0x3E, + CC2500_3F_TXFIFO = 0x3F, + CC2500_3F_RXFIFO = 0x3F +}; + +// Definitions for burst/single access to registers +#define CC2500_WRITE_SINGLE 0x00 +#define CC2500_WRITE_BURST 0x40 +#define CC2500_READ_SINGLE 0x80 +#define CC2500_READ_BURST 0xC0 + +// Strobe commands +#define CC2500_SRES 0x30 // Reset chip. +#define CC2500_SFSTXON \ + 0x31 // Enable and calibrate frequency synthesizer (if MCSM0.FS_AUTOCAL=1). + // If in RX/TX: Go to a wait state where only the synthesizer is + // running (for quick RX / TX turnaround). +#define CC2500_SXOFF 0x32 // Turn off crystal oscillator. +#define CC2500_SCAL 0x33 // Calibrate frequency synthesizer and turn it off + // (enables quick start). +#define CC2500_SRX \ + 0x34 // Enable RX. Perform calibration first if coming from IDLE and + // MCSM0.FS_AUTOCAL=1. +#define CC2500_STX \ + 0x35 // In IDLE state: Enable TX. Perform calibration first if + // MCSM0.FS_AUTOCAL=1. If in RX state and CCA is enabled: + // Only go to TX if channel is clear. +#define CC2500_SIDLE \ + 0x36 // Exit RX / TX, turn off frequency synthesizer and exit + // Wake-On-Radio mode if applicable. +#define CC2500_SAFC 0x37 // Perform AFC adjustment of the frequency synthesizer +#define CC2500_SWOR 0x38 // Start automatic RX polling sequence (Wake-on-Radio) +#define CC2500_SPWD 0x39 // Enter power down mode when CSn goes high. +#define CC2500_SFRX 0x3A // Flush the RX FIFO buffer. +#define CC2500_SFTX 0x3B // Flush the TX FIFO buffer. +#define CC2500_SWORRST 0x3C // Reset real time clock. +#define CC2500_SNOP \ + 0x3D // No operation. May be used to pad strobe commands to two + // bytes for simpler software. +//---------------------------------------------------------------------------------- +// Chip Status Byte +//---------------------------------------------------------------------------------- + +// Bit fields in the chip status byte +#define CC2500_STATUS_CHIP_RDYn_BM 0x80 +#define CC2500_STATUS_STATE_BM 0x70 +#define CC2500_STATUS_FIFO_BYTES_AVAILABLE_BM 0x0F + +// Chip states +#define CC2500_STATE_IDLE 0x00 +#define CC2500_STATE_RX 0x10 +#define CC2500_STATE_TX 0x20 +#define CC2500_STATE_FSTXON 0x30 +#define CC2500_STATE_CALIBRATE 0x40 +#define CC2500_STATE_SETTLING 0x50 +#define CC2500_STATE_RX_OVERFLOW 0x60 +#define CC2500_STATE_TX_UNDERFLOW 0x70 + +//---------------------------------------------------------------------------------- +// Other register bit fields +//---------------------------------------------------------------------------------- +#define CC2500_LQI_CRC_OK_BM 0x80 +#define CC2500_LQI_EST_BM 0x7F + +void cc2500ReadFifo(uint8_t *dpbuffer, uint8_t len); +void cc2500WriteFifo(uint8_t *dpbuffer, uint8_t len); + +void cc2500ReadRegisterMulti(uint8_t address, uint8_t *data, + uint8_t length); +void cc2500WriteRegisterMulti(uint8_t address, uint8_t *data, + uint8_t length); + +uint8_t cc2500ReadReg(uint8_t reg); +void cc2500Strobe(uint8_t address); +void cc2500WriteReg(uint8_t address, uint8_t data); +void cc2500SetPower(uint8_t power); +uint8_t cc2500Reset(void); + + +#endif diff --git a/sw/airborne/subsystems/datalink/frsky_x.c b/sw/airborne/subsystems/datalink/frsky_x.c new file mode 100644 index 0000000000..1a2b9b0bf2 --- /dev/null +++ b/sw/airborne/subsystems/datalink/frsky_x.c @@ -0,0 +1,171 @@ +/* + * Copyright (C) 2020 Tom van Dijk + * + * This file is part of paparazzi. + * + * paparazzi 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 2, or (at your option) + * any later version. + * + * paparazzi 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 paparazzi; see the file COPYING. If not, write to + * the Free Software Foundation, 59 Temple Place - Suite 330, + * Boston, MA 02111-1307, USA. + */ + +#include "subsystems/radio_control/cc2500_frsky/cc2500_smartport.h" +#include "subsystems/datalink/frsky_x.h" + +#include + +struct frsky_x_serial_periph frsky_x_serial; + + +/* Serial device */ +// Based on usb_ser_hw.c +// Generic fifo implementation +static void fifo_init(fifo_t *fifo, uint8_t *buf, size_t size); +static bool fifo_put(fifo_t *fifo, uint8_t c); +static bool fifo_get(fifo_t *fifo, uint8_t *pc); +static int fifo_avail(fifo_t *fifo); +static int fifo_free(fifo_t *fifo); + +static void fifo_init(fifo_t *fifo, uint8_t *buf, size_t size) { + fifo->head = 0; + fifo->tail = 0; + fifo->buf = buf; + fifo->size = size; +} + +static bool fifo_put(fifo_t *fifo, uint8_t c) { + int next; + + // check if FIFO has room + next = (fifo->head + 1) % fifo->size; + if (next == fifo->tail) { + // full + return false; + } + + fifo->buf[fifo->head] = c; + fifo->head = next; + + return true; +} + +static bool fifo_get(fifo_t *fifo, uint8_t *pc) { + int next; + + // check if FIFO has data + if (fifo->head == fifo->tail) { + return false; + } + + next = (fifo->tail + 1) % fifo->size; + + *pc = fifo->buf[fifo->tail]; + fifo->tail = next; + + return true; +} + +static int fifo_avail(fifo_t *fifo) { + return (fifo->size + fifo->head - fifo->tail) % fifo->size; +} + +static int fifo_free(fifo_t *fifo) { + return (fifo->size - 1 - fifo_avail(fifo)); +} + + +// Serial device functions +static int frsky_x_serial_check_free_space(void *p, long *fd, uint16_t len); +static void frsky_x_serial_put_byte(void *p, long fd, uint8_t c); +static void frsky_x_serial_put_buffer(void *p, long fd, const uint8_t *data, uint16_t len); +static void frsky_x_serial_send_message(void *p, long fd); +static int frsky_x_serial_char_available(void *p); +static uint8_t frsky_x_serial_get_byte(void *p); + +static int frsky_x_serial_check_free_space(void *p, long *fd, uint16_t len) { + (void) fd; + return (fifo_free(&((struct frsky_x_serial_periph *)p)->downlink_fifo) >= len ? true : false); +} + +static void frsky_x_serial_put_byte(void *p, long fd, uint8_t c) { + (void) fd; + fifo_put(&((struct frsky_x_serial_periph *)p)->downlink_fifo, c); +} + +static void frsky_x_serial_put_buffer(void *p, long fd, const uint8_t *data, uint16_t len) { + for (int i = 0; i < len; ++i) { + frsky_x_serial_put_byte(p, fd, data[i]); + } +} + +static void frsky_x_serial_send_message(void *p, long fd) { + (void) p; + (void) fd; + /* Do nothing, handled by smartPortDownlink_cb */ +} + +static int frsky_x_serial_char_available(void *p) { + return fifo_avail(&((struct frsky_x_serial_periph *)p)->uplink_fifo); +} + +static uint8_t frsky_x_serial_get_byte(void *p) { + uint8_t byte; + fifo_get(&((struct frsky_x_serial_periph *)p)->uplink_fifo, &byte); + return byte; +} + + +/* SmartPort sensor */ +static bool smartPortDownlink_cb(uint32_t *data) { + if (fifo_avail(&frsky_x_serial.downlink_fifo) >= 4) { + uint8_t data_u8[4]; + fifo_get(&frsky_x_serial.downlink_fifo, data_u8 + 0); + fifo_get(&frsky_x_serial.downlink_fifo, data_u8 + 1); + fifo_get(&frsky_x_serial.downlink_fifo, data_u8 + 2); + fifo_get(&frsky_x_serial.downlink_fifo, data_u8 + 3); + *data = + (data_u8[0] << 24) | + (data_u8[1] << 16) | + (data_u8[2] << 8) | + (data_u8[3]); + return true; + } + return false; +} + + +static void smartPortUplink_cb(smartPortPayload_t *payload) { + uint8_t shift = 24; + for (uint8_t i = 0; i < payload->frameId; ++i) { + fifo_put(&frsky_x_serial.uplink_fifo, (uint8_t)((payload->data >> shift) & 0xFF)); + shift -= 8; + } +} + + +void datalink_frsky_x_init(void) { + /* Set up link device */ + fifo_init(&frsky_x_serial.downlink_fifo, frsky_x_serial.downlink_buf, DOWNLINK_BUFFER_SIZE); + fifo_init(&frsky_x_serial.uplink_fifo, frsky_x_serial.uplink_buf, UPLINK_BUFFER_SIZE); + frsky_x_serial.device.periph = (void *)(&frsky_x_serial); + frsky_x_serial.device.check_free_space = frsky_x_serial_check_free_space; + frsky_x_serial.device.put_byte = frsky_x_serial_put_byte; + frsky_x_serial.device.put_buffer = frsky_x_serial_put_buffer; + frsky_x_serial.device.send_message = frsky_x_serial_send_message; + frsky_x_serial.device.char_available = frsky_x_serial_char_available; + frsky_x_serial.device.get_byte = frsky_x_serial_get_byte; + + /* Attach to SmartPort hooks */ + smartPortDownlink = smartPortDownlink_cb; + smartPortUplink = smartPortUplink_cb; +} diff --git a/sw/airborne/subsystems/datalink/frsky_x.h b/sw/airborne/subsystems/datalink/frsky_x.h new file mode 100644 index 0000000000..eac7538a00 --- /dev/null +++ b/sw/airborne/subsystems/datalink/frsky_x.h @@ -0,0 +1,51 @@ +/* + * Copyright (C) 2020 Tom van Dijk + * + * This file is part of paparazzi. + * + * paparazzi 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 2, or (at your option) + * any later version. + * + * paparazzi 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 paparazzi; see the file COPYING. If not, write to + * the Free Software Foundation, 59 Temple Place - Suite 330, + * Boston, MA 02111-1307, USA. + */ + +#ifndef DATALINK_FRSKY_X_H +#define DATALINK_FRSKY_X_H + +#include "pprzlink/pprzlink_device.h" + +#define DOWNLINK_BUFFER_SIZE 512 +#define UPLINK_BUFFER_SIZE 512 + +typedef struct { + int head; + int tail; + uint8_t *buf; + size_t size; +} fifo_t; + +struct frsky_x_serial_periph { + /** Generic device interface */ + struct link_device device; + /* Downlink fifo */ + fifo_t downlink_fifo; + uint8_t downlink_buf[DOWNLINK_BUFFER_SIZE]; + /* Uplink fifo */ + fifo_t uplink_fifo; + uint8_t uplink_buf[UPLINK_BUFFER_SIZE]; +}; +extern struct frsky_x_serial_periph frsky_x_serial; + +void datalink_frsky_x_init(void); + +#endif // DATALINK_FRSKY_X_H diff --git a/sw/airborne/subsystems/radio_control/cc2500_frsky/cc2500_common.c b/sw/airborne/subsystems/radio_control/cc2500_frsky/cc2500_common.c new file mode 100644 index 0000000000..f9fae7987c --- /dev/null +++ b/sw/airborne/subsystems/radio_control/cc2500_frsky/cc2500_common.c @@ -0,0 +1,180 @@ +#include "cc2500_compat.h" + +#include "peripherals/cc2500.h" +#include "cc2500_settings.h" +#include "cc2500_common.h" +#include "cc2500_rx.h" + +// betaflight/src/main/rx/cc2500_common.c @ 50bbe0b +/* + * This file is part of Cleanflight and Betaflight. + * + * Cleanflight and Betaflight are free software. You can redistribute + * this software and/or modify this software under the terms of the + * GNU General Public License as published by the Free Software + * Foundation, either version 3 of the License, or (at your option) + * any later version. + * + * Cleanflight and Betaflight are distributed in the hope that they + * will be useful, but WITHOUT ANY WARRANTY; without even the implied + * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + * See the GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this software. + * + * If not, see . + */ + +#include + +//#include "platform.h" + +#if defined(USE_RX_FRSKY_SPI) || defined(USE_RX_SFHSS_SPI) + +//#include "common/maths.h" +// +//#include "drivers/io.h" +//#include "drivers/rx/rx_cc2500.h" +//#include "drivers/time.h" +// +//#include "fc/config.h" +// +//#include "pg/pg.h" +//#include "pg/pg_ids.h" +//#include "pg/rx.h" +//#include "pg/rx_spi.h" +//#include "pg/rx_spi_cc2500.h" +// +//#include "rx/rx.h" +//#include "rx/rx_spi.h" +// +//#include "cc2500_common.h" + +static IO_t gdoPin; +#if defined(USE_RX_CC2500_SPI_PA_LNA) +static IO_t txEnPin; +static IO_t rxLnaEnPin; +#if defined(USE_RX_CC2500_SPI_DIVERSITY) +static IO_t antSelPin; +#endif +#endif +static int16_t rssiDbm; + +uint16_t cc2500getRssiDbm(void) +{ + return rssiDbm; +} + +void cc2500setRssiDbm(uint8_t value) +{ + if (value >= 128) { + rssiDbm = ((((uint16_t)value) * 18) >> 5) - 82; + } else { + rssiDbm = ((((uint16_t)value) * 18) >> 5) + 65; + } + + setRssi(rssiDbm << 3, RSSI_SOURCE_RX_PROTOCOL); +} + +bool cc2500getGdo(void) +{ + return IORead(gdoPin); +} + +#if defined(USE_RX_CC2500_SPI_PA_LNA) && defined(USE_RX_CC2500_SPI_DIVERSITY) +void cc2500switchAntennae(void) +{ + static bool alternativeAntennaSelected = true; + + if (antSelPin) { + if (alternativeAntennaSelected) { + IOLo(antSelPin); + } else { + IOHi(antSelPin); + } + alternativeAntennaSelected = !alternativeAntennaSelected; + } +} +#endif +#if defined(USE_RX_CC2500_SPI_PA_LNA) +void cc2500TxEnable(void) +{ + if (txEnPin) { + IOHi(txEnPin); + } +} + +void cc2500TxDisable(void) +{ + if (txEnPin) { + IOLo(txEnPin); + } +} +#endif + +static bool cc2500SpiDetect(void) +{ + const uint8_t chipPartNum = cc2500ReadReg(CC2500_30_PARTNUM | CC2500_READ_BURST); //CC2500 read registers chip part num + const uint8_t chipVersion = cc2500ReadReg(CC2500_31_VERSION | CC2500_READ_BURST); //CC2500 read registers chip version + if (chipPartNum == 0x80 && chipVersion == 0x03) { + return true; + } + + return false; +} + +bool cc2500SpiInit(void) +{ + if (rxCc2500SpiConfig()->chipDetectEnabled && !cc2500SpiDetect()) { + return false; + } + + // gpio init here + gdoPin = IOGetByTag(rxSpiConfig()->extiIoTag); + + if (!gdoPin) { + return false; + } + + IOInit(gdoPin, OWNER_RX_SPI_EXTI, 0); + IOConfigGPIO(gdoPin, IOCFG_IN_FLOATING); +#if defined(USE_RX_CC2500_SPI_PA_LNA) + if (rxCc2500SpiConfig()->lnaEnIoTag) { + rxLnaEnPin = IOGetByTag(rxCc2500SpiConfig()->lnaEnIoTag); + IOInit(rxLnaEnPin, OWNER_RX_SPI_CC2500_LNA_EN, 0); + IOConfigGPIO(rxLnaEnPin, IOCFG_OUT_PP); + + IOHi(rxLnaEnPin); // always on at the moment + } + if (rxCc2500SpiConfig()->txEnIoTag) { + txEnPin = IOGetByTag(rxCc2500SpiConfig()->txEnIoTag); + IOInit(txEnPin, OWNER_RX_SPI_CC2500_TX_EN, 0); + IOConfigGPIO(txEnPin, IOCFG_OUT_PP); + } else { + txEnPin = IO_NONE; + } +#if defined(USE_RX_CC2500_SPI_DIVERSITY) + if (rxCc2500SpiConfig()->antSelIoTag) { + antSelPin = IOGetByTag(rxCc2500SpiConfig()->antSelIoTag); + IOInit(antSelPin, OWNER_RX_SPI_CC2500_ANT_SEL, 0); + IOConfigGPIO(antSelPin, IOCFG_OUT_PP); + + IOHi(antSelPin); + } else { + antSelPin = IO_NONE; + } +#endif +#endif // USE_RX_CC2500_SPI_PA_LNA + +#if defined(USE_RX_CC2500_SPI_PA_LNA) + cc2500TxDisable(); +#endif // USE_RX_CC2500_SPI_PA_LNA + + if (rssiSource == RSSI_SOURCE_NONE) { + rssiSource = RSSI_SOURCE_RX_PROTOCOL; + } + + return true; +} +#endif diff --git a/sw/airborne/subsystems/radio_control/cc2500_frsky/cc2500_common.h b/sw/airborne/subsystems/radio_control/cc2500_frsky/cc2500_common.h new file mode 100644 index 0000000000..d5592c8663 --- /dev/null +++ b/sw/airborne/subsystems/radio_control/cc2500_frsky/cc2500_common.h @@ -0,0 +1,40 @@ +#include "cc2500_compat.h" + +#include "cc2500_rx_spi.h" + +// betaflight/src/main/rx/cc2500_common.h @ 50bbe0b on Jul 1 +/* + * This file is part of Cleanflight and Betaflight. + * + * Cleanflight and Betaflight are free software. You can redistribute + * this software and/or modify this software under the terms of the + * GNU General Public License as published by the Free Software + * Foundation, either version 3 of the License, or (at your option) + * any later version. + * + * Cleanflight and Betaflight are distributed in the hope that they + * will be useful, but WITHOUT ANY WARRANTY; without even the implied + * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + * See the GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this software. + * + * If not, see . + */ + +#pragma once + +//#include "rx/rx_spi.h" + +uint16_t cc2500getRssiDbm(void); +void cc2500setRssiDbm(uint8_t value); +bool cc2500getGdo(void); +#if defined(USE_RX_CC2500_SPI_PA_LNA) && defined(USE_RX_CC2500_SPI_DIVERSITY) +void cc2500switchAntennae(void); +#endif +#if defined(USE_RX_CC2500_SPI_PA_LNA) +void cc2500TxEnable(void); +void cc2500TxDisable(void); +#endif +bool cc2500SpiInit(void); diff --git a/sw/airborne/subsystems/radio_control/cc2500_frsky/cc2500_compat.c b/sw/airborne/subsystems/radio_control/cc2500_frsky/cc2500_compat.c new file mode 100644 index 0000000000..81fc89571f --- /dev/null +++ b/sw/airborne/subsystems/radio_control/cc2500_frsky/cc2500_compat.c @@ -0,0 +1,199 @@ +/* + * Copyright (C) 2019 Tom van Dijk + * + * This code is based on the betaflight cc2500 and FrskyX implementation. + * https://github.com/betaflight/betaflight + * + * This file is part of paparazzi. + * + * paparazzi 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 2, or (at your option) + * any later version. + * + * paparazzi 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 paparazzi; see the file COPYING. If not, write to + * the Free Software Foundation, 59 Temple Place - Suite 330, + * Boston, MA 02111-1307, USA. + */ + +#include "cc2500_compat.h" + +#include "state.h" +#include "mcu_periph/adc.h" +#include "mcu_periph/gpio.h" +#include "mcu_periph/sys_time.h" +#include "subsystems/electrical.h" + +#include +#include +#include + + +// (unknown): +struct attitude_t bf_attitude = { { 0, 0, 0 } }; // Dummy values + + +// main/config/config.h: +struct pidProfile_s *currentPidProfile; // Dummy values + + +// main/config/feature.h: +bool bf_featureIsEnabled(const uint32_t mask) { + uint32_t features = FEATURE_RX_SPI | FEATURE_TELEMETRY; + return features & mask; +} + + +// main/common/filters.h: +#define M_PI_FLOAT 3.14159265358979323846f +float pt1FilterGain(float f_cut, float dT) +{ + float RC = 1 / ( 2 * M_PI_FLOAT * f_cut); + return dT / (RC + dT); +} + +void pt1FilterInit(pt1Filter_t *filter, float k) { + filter->state = 0.0f; + filter->k = k; +} + +void pt1FilterUpdateCutoff(pt1Filter_t *filter, float k) { + filter->k = k; +} + +float pt1FilterApply(pt1Filter_t *filter, float input) { + filter->state = filter->state + filter->k * (input - filter->state); + return filter->state; +} + + +// main/drivers/time.h: +void bf_delayMicroseconds(timeUs_t us) { + sys_time_usleep(us); +} + +void bf_delay(timeMs_t ms) { + bf_delayMicroseconds(ms * 1000); +} + +timeUs_t bf_micros(void) { + return get_sys_time_usec(); +} + +timeMs_t bf_millis(void) { + return get_sys_time_msec(); +} + + +// main/drivers/adc.h: +uint16_t bf_adcGetChannel(uint8_t channel) { + (void) channel; + // Return current, as voltage is already reported by getLegacyBatteryVoltage + return (uint16_t)(electrical.current * 10000.0); // Assumed in 0.1mA +} + + +// main/drivers/rx_spi.h: +bool bf_rxSpiDeviceInit(void) { + return TRUE; +} + + +// main/drivers/io.h: +IO_t bf_IOGetByTag(ioTag_t io) { + return (IO_t)io; +} + +void bf_IOInit(IO_t io, uint8_t owner, uint8_t index) { + (void) io; + (void) owner; + (void) index; +} + +void bf_IOConfigGPIO(IO_t io, enum ioconfig_t cfg) { + if (!io) return; + switch(cfg) { + case IOCFG_OUT_PP: + gpio_setup_output(io->port, io->pin); + break; + case IOCFG_IN_FLOATING: + gpio_setup_input(io->port, io->pin); + break; + case IOCFG_IPU: + gpio_setup_input_pullup(io->port, io->pin); + break; + default: + assert("Invalid IO config" == NULL); + break; + } +} + +bool bf_IORead(IO_t gpio) { + if (!gpio) return 0; + return gpio_get(gpio->port, gpio->pin); +} + +void bf_IOHi(IO_t io) { + if (!io) return; + io->hi(io->port, io->pin); +} + +void bf_IOLo(IO_t io) { + if (!io) return; + io->lo(io->port, io->pin); +} + +void bf_IOToggle(IO_t io) { + if (!io) return; + gpio_toggle(io->port, io->pin); +} + + +// main/fc/controlrate_profile.h: +controlRateConfig_t *currentControlRateProfile; // Dummy values + + +// main/flight/position.h: +int32_t bf_getEstimatedAltitudeCm(void) { + return (int32_t)(stateGetPositionEnu_f()->z * 100.0); +} + +int16_t bf_getEstimatedVario(void) { + return (int16_t)(stateGetSpeedEnu_f()->z * 100.0); +} + + +// main/sensors/battery.h +bool bf_isBatteryVoltageConfigured(void) { + return TRUE; +} + +uint16_t bf_getLegacyBatteryVoltage(void) { + return (uint16_t)((electrical.vsupply * 100.0 + 5) / 10.0); // ??? +} + +uint16_t bf_getBatteryVoltage(void) { + return (uint16_t)(electrical.vsupply * 100.0); // 0.01V +} + +uint8_t bf_getBatteryCellCount(void) { + return 0; +} + +bool bf_isAmperageConfigured(void) { + return TRUE; +} + +int32_t bf_getAmperage(void) { + return (int32_t)(electrical.current * 100.0); +} + +int32_t bf_getMAhDrawn(void) { + return (int32_t)(electrical.charge * 1000.0); +} diff --git a/sw/airborne/subsystems/radio_control/cc2500_frsky/cc2500_compat.h b/sw/airborne/subsystems/radio_control/cc2500_frsky/cc2500_compat.h new file mode 100644 index 0000000000..2019e1b164 --- /dev/null +++ b/sw/airborne/subsystems/radio_control/cc2500_frsky/cc2500_compat.h @@ -0,0 +1,286 @@ +/* + * Copyright (C) 2019 Tom van Dijk + * + * This code is based on the betaflight cc2500 and FrskyX implementation. + * https://github.com/betaflight/betaflight + * + * This file is part of paparazzi. + * + * paparazzi 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 2, or (at your option) + * any later version. + * + * paparazzi 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 paparazzi; see the file COPYING. If not, write to + * the Free Software Foundation, 59 Temple Place - Suite 330, + * Boston, MA 02111-1307, USA. + */ + +/* + * This file contains compatibility code for the betaflight cc2500 frsky + * drivers. + * + * Notes: + * - Function macros are used so that betaflight names can be used when this + * header is included, while the actual functions can have a bf_ prefix to + * prevent possible name collisions. + */ + +#ifndef RADIO_CONTROL_CC2500_COMPAT_H +#define RADIO_CONTROL_CC2500_COMPAT_H + + +#pragma GCC diagnostic ignored "-Wmissing-prototypes" +#pragma GCC diagnostic ignored "-Wstrict-prototypes" +#pragma GCC diagnostic ignored "-Wswitch-default" +#pragma GCC diagnostic ignored "-Wmaybe-uninitialized" +#pragma GCC diagnostic ignored "-Wshadow" + + +#include +#include +#include + +#define USE_RX_SPI +#define USE_RX_FRSKY_SPI +#define USE_RX_FRSKY_SPI_TELEMETRY + +#if (CC2500_RX_SPI_PROTOCOL == RX_SPI_FRSKY_X_LBT) || (CC2500_RX_SPI_PROTOCOL == RX_SPI_FRSKY_X) +#define USE_RX_FRSKY_SPI_X +#define USE_TELEMETRY_SMARTPORT +#endif +#if (CC2500_RX_SPI_PROTOCOL == RX_SPI_FRSKY_D) +#define USE_RX_FRSKY_SPI_D +#endif + +#define DEBUG_SET(...) /* Do nothing */ +#define STATIC_ASSERT(...) /* Do nothing */ +#define STATIC_UNIT_TESTED static + + +// (unknown): +#define sensors(...) 1 + +struct attitude_values_t { + int8_t roll; + int8_t pitch; + int8_t yaw; +}; +struct attitude_t { + struct attitude_values_t values; +}; +extern struct attitude_t bf_attitude; +#define attitude bf_attitude + + +// main/common/utils.h: +#if __GNUC__ > 6 +#define FALLTHROUGH __attribute__ ((fallthrough)) +#else +#define FALLTHROUGH do {} while(0) +#endif + + +// main/common/time.h: +typedef int32_t timeDelta_t; +typedef uint32_t timeMs_t ; +typedef uint32_t timeUs_t; +#define TIMEUS_MAX UINT32_MAX + +static inline timeDelta_t cmpTimeUs(timeUs_t a, timeUs_t b) { return (timeDelta_t)(a - b); } + + +// main/common/maths.h: +#define MIN(a,b) \ + __extension__ ({ __typeof__ (a) _a = (a); \ + __typeof__ (b) _b = (b); \ + _a < _b ? _a : _b; }) + + +// main/common/filter.h: +typedef struct pt1Filter_s { + float state; + float k; +} pt1Filter_t; + +float pt1FilterGain(float f_cut, float dT); +void pt1FilterInit(pt1Filter_t *filter, float k); +void pt1FilterUpdateCutoff(pt1Filter_t *filter, float k); +float pt1FilterApply(pt1Filter_t *filter, float input); + + +// main/config/config.h: +#define PID_ROLL 0 +#define PID_PITCH 0 +#define PID_YAW 0 + +struct pidGains_s { + uint8_t P; + uint8_t I; + uint8_t D; +}; +struct pidProfile_s { + struct pidGains_s pid[1]; +}; +extern struct pidProfile_s *currentPidProfile; + + +// main/config/feature.h: +typedef enum { + FEATURE_RX_PPM = 1 << 0, +// FEATURE_INFLIGHT_ACC_CAL = 1 << 2, + FEATURE_RX_SERIAL = 1 << 3, +// FEATURE_MOTOR_STOP = 1 << 4, +// FEATURE_SERVO_TILT = 1 << 5, +// FEATURE_SOFTSERIAL = 1 << 6, +// FEATURE_GPS = 1 << 7, +// FEATURE_RANGEFINDER = 1 << 9, + FEATURE_TELEMETRY = 1 << 10, +// FEATURE_3D = 1 << 12, + FEATURE_RX_PARALLEL_PWM = 1 << 13, + FEATURE_RX_MSP = 1 << 14, + FEATURE_RSSI_ADC = 1 << 15, +// FEATURE_LED_STRIP = 1 << 16, +// FEATURE_DASHBOARD = 1 << 17, +// FEATURE_OSD = 1 << 18, +// FEATURE_CHANNEL_FORWARDING = 1 << 20, +// FEATURE_TRANSPONDER = 1 << 21, +// FEATURE_AIRMODE = 1 << 22, + FEATURE_RX_SPI = 1 << 25, +// //FEATURE_SOFTSPI = 1 << 26, (removed) +// FEATURE_ESC_SENSOR = 1 << 27, +// FEATURE_ANTI_GRAVITY = 1 << 28, +// FEATURE_DYNAMIC_FILTER = 1 << 29, +} features_e; + +bool bf_featureIsEnabled(const uint32_t mask); +#define featureIsEnabled(mask) bf_featureIsEnabled(mask) + + +// main/drivers/time.h: +void bf_delayMicroseconds(timeUs_t us); +#define delayMicroseconds(us) bf_delayMicroseconds(us) + +void bf_delay(timeMs_t ms); +#define delay(ms) bf_delay(ms) + +timeUs_t bf_micros(void); +#define micros() bf_micros() +timeMs_t bf_millis(void); +#define millis() bf_millis() + + +// main/drivers/adc.h: +#define ADC_EXTERNAL1 1 +uint16_t bf_adcGetChannel(uint8_t channel); +#define adcGetChannel(channel) bf_adcGetChannel(channel) + + +// main/drivers/rx/rx_spi.h: +#define RX_SPI_MAX_PAYLOAD_SIZE 35 + +bool bf_rxSpiDeviceInit(void); +#define rxSpiDeviceInit(rxSpiConfig) bf_rxSpiDeviceInit() + + +// main/drivers/rx/rx_pwm.h: +#define PPM_RCVR_TIMEOUT 0 + + +// main/drivers/io.h: +typedef void(*gpiofnptr_t)(uint32_t port, uint16_t pin); + +struct gpio_t { + uint32_t port; + uint16_t pin; + gpiofnptr_t hi; + gpiofnptr_t lo; +}; +typedef struct gpio_t *IO_t; +typedef IO_t ioTag_t; +#define IO_NONE NULL + +IO_t bf_IOGetByTag(ioTag_t io); +#define IOGetByTag(io) bf_IOGetByTag(io) + +void bf_IOInit(IO_t io, uint8_t owner, uint8_t index); +#define IOInit(io, owner, index) bf_IOInit(io, owner, index) + +enum ioconfig_t { + IOCFG_OUT_PP, + IOCFG_IN_FLOATING, + IOCFG_IPU, +}; +void bf_IOConfigGPIO(IO_t io, enum ioconfig_t cfg); +#define IOConfigGPIO(io, cfg) bf_IOConfigGPIO(io, cfg) + +bool bf_IORead(IO_t gpio); +#define IORead(gpio) bf_IORead(gpio) + +void bf_IOHi(IO_t io); +#define IOHi(io) bf_IOHi(io) +void bf_IOLo(IO_t io); +#define IOLo(io) bf_IOLo(io) +void bf_IOToggle(IO_t io); +#define IOToggle(io) bf_IOToggle(io) + + +// main/fc/runtime_config.h: +#define isArmingDisabled() 0 +#define ARMING_FLAG(...) 1 +#define FLIGHT_MODE(...) 0 + + +// main/fc/controlrate_profile.h: +#define FD_ROLL 0 +#define FD_PITCH 0 +#define FD_YAW 0 +typedef struct { + uint8_t rates[1]; +} controlRateConfig_t; +extern controlRateConfig_t *currentControlRateProfile; + + +// main/flight/position.h: +int32_t bf_getEstimatedAltitudeCm(void); +#define getEstimatedAltitudeCm() bf_getEstimatedAltitudeCm() + +int16_t bf_getEstimatedVario(void); +#define getEstimatedVario() bf_getEstimatedVario() + + +// main/drivers/resources.h: +typedef enum { + OWNER_RX_SPI_EXTI, + OWNER_RX_SPI_BIND, + OWNER_LED, +} resourceOwner_e; + + +// main/sensors/battery.h +bool bf_isBatteryVoltageConfigured(void); +#define isBatteryVoltageConfigured() bf_isBatteryVoltageConfigured() + +uint16_t bf_getLegacyBatteryVoltage(void); +#define getLegacyBatteryVoltage() bf_getLegacyBatteryVoltage() +uint16_t bf_getBatteryVoltage(void); +#define getBatteryVoltage() bf_getBatteryVoltage() + +uint8_t bf_getBatteryCellCount(void); +#define getBatteryCellCount() bf_getBatteryCellCount() + +bool bf_isAmperageConfigured(void); +#define isAmperageConfigured() bf_isAmperageConfigured() +int32_t bf_getAmperage(void); +#define getAmperage() bf_getAmperage() +int32_t bf_getMAhDrawn(void); +#define getMAhDrawn() bf_getMAhDrawn() + + +#endif // RADIO_CONTROL_CC2500_COMPAT_H diff --git a/sw/airborne/subsystems/radio_control/cc2500_frsky/cc2500_frsky_common.h b/sw/airborne/subsystems/radio_control/cc2500_frsky/cc2500_frsky_common.h new file mode 100644 index 0000000000..98f8115464 --- /dev/null +++ b/sw/airborne/subsystems/radio_control/cc2500_frsky/cc2500_frsky_common.h @@ -0,0 +1,32 @@ +#include "cc2500_compat.h" +#include "cc2500_settings.h" + +// betaflight/src/main/rx/cc2500_frsky_common.h @ 766c90b +/* + * This file is part of Cleanflight and Betaflight. + * + * Cleanflight and Betaflight are free software. You can redistribute + * this software and/or modify this software under the terms of the + * GNU General Public License as published by the Free Software + * Foundation, either version 3 of the License, or (at your option) + * any later version. + * + * Cleanflight and Betaflight are distributed in the hope that they + * will be useful, but WITHOUT ANY WARRANTY; without even the implied + * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + * See the GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this software. + * + * If not, see . + */ + +#pragma once + +//#include "rx/rx_spi.h" + +bool frSkySpiInit(const rxSpiConfig_t *rxSpiConfig, rxRuntimeConfig_t *rxRuntimeConfig); +rx_spi_received_e frSkySpiDataReceived(uint8_t *packet); +rx_spi_received_e frSkySpiProcessFrame(uint8_t *packet); +void frSkySpiSetRcData(uint16_t *rcData, const uint8_t *payload); diff --git a/sw/airborne/subsystems/radio_control/cc2500_frsky/cc2500_frsky_d.h b/sw/airborne/subsystems/radio_control/cc2500_frsky/cc2500_frsky_d.h new file mode 100644 index 0000000000..cf818987ef --- /dev/null +++ b/sw/airborne/subsystems/radio_control/cc2500_frsky/cc2500_frsky_d.h @@ -0,0 +1,20 @@ +/* TODO PLACEHOLDER CODE! */ +#include "cc2500_compat.h" + +#define RC_CHANNEL_COUNT_FRSKY_D 8 + +static rx_spi_received_e frSkyDHandlePacket(uint8_t * const packet, uint8_t * const protocolState) { + (void) packet; + (void) protocolState; + return RX_SPI_RECEIVED_NONE; +} + +static void frSkyDSetRcData(uint16_t *rcData, const uint8_t *payload) { + (void) rcData; + (void) payload; + return; +} + +static void frSkyDInit(void) { + return; +} diff --git a/sw/airborne/subsystems/radio_control/cc2500_frsky/cc2500_frsky_shared.c b/sw/airborne/subsystems/radio_control/cc2500_frsky/cc2500_frsky_shared.c new file mode 100644 index 0000000000..159e9d23ef --- /dev/null +++ b/sw/airborne/subsystems/radio_control/cc2500_frsky/cc2500_frsky_shared.c @@ -0,0 +1,482 @@ +#include "cc2500_compat.h" + +#include "peripherals/cc2500.h" +#include "cc2500_settings.h" +#include "cc2500_rx_spi_common.h" +#include "cc2500_common.h" +#include "cc2500_frsky_common.h" +#include "cc2500_frsky_d.h" +#include "cc2500_frsky_x.h" +#include "cc2500_frsky_shared.h" + +// betaflight/src/main/rx/cc2500_frsky_shared.c @ 766c90b +/* + * This file is part of Cleanflight and Betaflight. + * + * Cleanflight and Betaflight are free software. You can redistribute + * this software and/or modify this software under the terms of the + * GNU General Public License as published by the Free Software + * Foundation, either version 3 of the License, or (at your option) + * any later version. + * + * Cleanflight and Betaflight are distributed in the hope that they + * will be useful, but WITHOUT ANY WARRANTY; without even the implied + * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + * See the GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this software. + * + * If not, see . + */ + +#include + +//#include "platform.h" + +#ifdef USE_RX_FRSKY_SPI + +//#include "common/maths.h" +// +//#include "drivers/rx/rx_cc2500.h" +//#include "drivers/io.h" +//#include "drivers/time.h" +// +//#include "fc/config.h" +// +//#include "pg/rx.h" +//#include "pg/rx_spi.h" +//#include "pg/rx_spi_cc2500.h" +// +//#include "rx/rx.h" +//#include "rx/rx_spi.h" +//#include "rx/rx_spi_common.h" +// +//#include "rx/cc2500_common.h" +//#include "rx/cc2500_frsky_common.h" +//#include "rx/cc2500_frsky_d.h" +//#include "rx/cc2500_frsky_x.h" +// +//#include "cc2500_frsky_shared.h" + +static rx_spi_protocol_e spiProtocol; + +static timeMs_t start_time; +static uint8_t protocolState; + +uint32_t missingPackets; +timeDelta_t timeoutUs; + +static uint8_t calData[255][3]; +static timeMs_t timeTunedMs; +uint8_t listLength; +static uint8_t bindIdx; +static int8_t bindOffset; + +typedef uint8_t handlePacketFn(uint8_t * const packet, uint8_t * const protocolState); +typedef rx_spi_received_e processFrameFn(uint8_t * const packet); +typedef void setRcDataFn(uint16_t *rcData, const uint8_t *payload); + +static handlePacketFn *handlePacket; +static processFrameFn *processFrame; +static setRcDataFn *setRcData; + +static void initialise() { + cc2500Reset(); + cc2500WriteReg(CC2500_02_IOCFG0, 0x01); + cc2500WriteReg(CC2500_18_MCSM0, 0x18); + cc2500WriteReg(CC2500_07_PKTCTRL1, 0x04); + cc2500WriteReg(CC2500_3E_PATABLE, 0xFF); + cc2500WriteReg(CC2500_0C_FSCTRL0, 0x00); + cc2500WriteReg(CC2500_0D_FREQ2, 0x5C); + cc2500WriteReg(CC2500_13_MDMCFG1, 0x23); + cc2500WriteReg(CC2500_14_MDMCFG0, 0x7A); + cc2500WriteReg(CC2500_19_FOCCFG, 0x16); + cc2500WriteReg(CC2500_1A_BSCFG, 0x6C); + cc2500WriteReg(CC2500_1B_AGCCTRL2, 0x03); + cc2500WriteReg(CC2500_1C_AGCCTRL1, 0x40); + cc2500WriteReg(CC2500_1D_AGCCTRL0, 0x91); + cc2500WriteReg(CC2500_21_FREND1, 0x56); + cc2500WriteReg(CC2500_22_FREND0, 0x10); + cc2500WriteReg(CC2500_23_FSCAL3, 0xA9); + cc2500WriteReg(CC2500_24_FSCAL2, 0x0A); + cc2500WriteReg(CC2500_25_FSCAL1, 0x00); + cc2500WriteReg(CC2500_26_FSCAL0, 0x11); + cc2500WriteReg(CC2500_29_FSTEST, 0x59); + cc2500WriteReg(CC2500_2C_TEST2, 0x88); + cc2500WriteReg(CC2500_2D_TEST1, 0x31); + cc2500WriteReg(CC2500_2E_TEST0, 0x0B); + cc2500WriteReg(CC2500_03_FIFOTHR, 0x07); + cc2500WriteReg(CC2500_09_ADDR, 0x00); + + switch (spiProtocol) { + case RX_SPI_FRSKY_D: + cc2500WriteReg(CC2500_17_MCSM1, 0x0C); + cc2500WriteReg(CC2500_0E_FREQ1, 0x76); + cc2500WriteReg(CC2500_0F_FREQ0, 0x27); + cc2500WriteReg(CC2500_06_PKTLEN, 0x19); + cc2500WriteReg(CC2500_08_PKTCTRL0, 0x05); + cc2500WriteReg(CC2500_0B_FSCTRL1, 0x08); + cc2500WriteReg(CC2500_10_MDMCFG4, 0xAA); + cc2500WriteReg(CC2500_11_MDMCFG3, 0x39); + cc2500WriteReg(CC2500_12_MDMCFG2, 0x11); + cc2500WriteReg(CC2500_15_DEVIATN, 0x42); + + break; + case RX_SPI_FRSKY_X: + cc2500WriteReg(CC2500_17_MCSM1, 0x0C); + cc2500WriteReg(CC2500_0E_FREQ1, 0x76); + cc2500WriteReg(CC2500_0F_FREQ0, 0x27); + cc2500WriteReg(CC2500_06_PKTLEN, 0x1E); + cc2500WriteReg(CC2500_08_PKTCTRL0, 0x01); + cc2500WriteReg(CC2500_0B_FSCTRL1, 0x0A); + cc2500WriteReg(CC2500_10_MDMCFG4, 0x7B); + cc2500WriteReg(CC2500_11_MDMCFG3, 0x61); + cc2500WriteReg(CC2500_12_MDMCFG2, 0x13); + cc2500WriteReg(CC2500_15_DEVIATN, 0x51); + + break; + case RX_SPI_FRSKY_X_LBT: + cc2500WriteReg(CC2500_17_MCSM1, 0x0E); + cc2500WriteReg(CC2500_0E_FREQ1, 0x80); + cc2500WriteReg(CC2500_0F_FREQ0, 0x00); + cc2500WriteReg(CC2500_06_PKTLEN, 0x23); + cc2500WriteReg(CC2500_08_PKTCTRL0, 0x01); + cc2500WriteReg(CC2500_0B_FSCTRL1, 0x08); + cc2500WriteReg(CC2500_10_MDMCFG4, 0x7B); + cc2500WriteReg(CC2500_11_MDMCFG3, 0xF8); + cc2500WriteReg(CC2500_12_MDMCFG2, 0x03); + cc2500WriteReg(CC2500_15_DEVIATN, 0x53); + + break; + default: + + break; + } + + for(unsigned c = 0;c < 0xFF; c++) + { //calibrate all channels + cc2500Strobe(CC2500_SIDLE); + cc2500WriteReg(CC2500_0A_CHANNR, c); + cc2500Strobe(CC2500_SCAL); + delayMicroseconds(900); // + calData[c][0] = cc2500ReadReg(CC2500_23_FSCAL3); + calData[c][1] = cc2500ReadReg(CC2500_24_FSCAL2); + calData[c][2] = cc2500ReadReg(CC2500_25_FSCAL1); + } +} + +void initialiseData(bool inBindState) +{ + cc2500WriteReg(CC2500_0C_FSCTRL0, (uint8_t)rxCc2500SpiConfig()->bindOffset); + cc2500WriteReg(CC2500_18_MCSM0, 0x8); + cc2500WriteReg(CC2500_09_ADDR, inBindState ? 0x03 : rxCc2500SpiConfig()->bindTxId[0]); + cc2500WriteReg(CC2500_07_PKTCTRL1, 0x0D); + cc2500WriteReg(CC2500_19_FOCCFG, 0x16); + if (!inBindState) { + cc2500WriteReg(CC2500_03_FIFOTHR, 0x14); + } + delay(10); +} + +static void initTuneRx(void) +{ + cc2500WriteReg(CC2500_19_FOCCFG, 0x14); + timeTunedMs = millis(); + bindOffset = -126; + cc2500WriteReg(CC2500_0C_FSCTRL0, (uint8_t)bindOffset); + cc2500WriteReg(CC2500_07_PKTCTRL1, 0x0C); + cc2500WriteReg(CC2500_18_MCSM0, 0x8); + + cc2500Strobe(CC2500_SIDLE); + cc2500WriteReg(CC2500_23_FSCAL3, calData[0][0]); + cc2500WriteReg(CC2500_24_FSCAL2, calData[0][1]); + cc2500WriteReg(CC2500_25_FSCAL1, calData[0][2]); + cc2500WriteReg(CC2500_0A_CHANNR, 0); + cc2500Strobe(CC2500_SFRX); + cc2500Strobe(CC2500_SRX); +} + +static bool tuneRx(uint8_t *packet) +{ + if (bindOffset >= 126) { + bindOffset = -126; + } + if ((millis() - timeTunedMs) > 50) { + timeTunedMs = millis(); + bindOffset += 5; + cc2500WriteReg(CC2500_0C_FSCTRL0, (uint8_t)bindOffset); + } + if (cc2500getGdo()) { + uint8_t ccLen = cc2500ReadReg(CC2500_3B_RXBYTES | CC2500_READ_BURST) & 0x7F; + if (ccLen) { + cc2500ReadFifo(packet, ccLen); + if (packet[ccLen - 1] & 0x80) { + if (packet[2] == 0x01) { + uint8_t Lqi = packet[ccLen - 1] & 0x7F; + // higher lqi represent better link quality + if (Lqi > 50) { + rxCc2500SpiConfigMutable()->bindOffset = bindOffset; + return true; + } + } + } + } + } + + return false; +} + +static void initGetBind(void) +{ + cc2500Strobe(CC2500_SIDLE); + cc2500WriteReg(CC2500_23_FSCAL3, calData[0][0]); + cc2500WriteReg(CC2500_24_FSCAL2, calData[0][1]); + cc2500WriteReg(CC2500_25_FSCAL1, calData[0][2]); + cc2500WriteReg(CC2500_0A_CHANNR, 0); + cc2500Strobe(CC2500_SFRX); + delayMicroseconds(20); // waiting flush FIFO + + cc2500Strobe(CC2500_SRX); + listLength = 0; + bindIdx = 0x05; +} + +static bool getBind1(uint8_t *packet) +{ + // len|bind |tx + // id|03|01|idx|h0|h1|h2|h3|h4|00|00|00|00|00|00|00|00|00|00|00|00|00|00|00|CHK1|CHK2|RSSI|LQI/CRC| + // Start by getting bind packet 0 and the txid + if (cc2500getGdo()) { + uint8_t ccLen = cc2500ReadReg(CC2500_3B_RXBYTES | CC2500_READ_BURST) & 0x7F; + if (ccLen) { + cc2500ReadFifo(packet, ccLen); + if (packet[ccLen - 1] & 0x80) { + if (packet[2] == 0x01) { + if (packet[5] == 0x00) { + rxCc2500SpiConfigMutable()->bindTxId[0] = packet[3]; + rxCc2500SpiConfigMutable()->bindTxId[1] = packet[4]; + for (uint8_t n = 0; n < 5; n++) { + rxCc2500SpiConfigMutable()->bindHopData[packet[5] + n] = + packet[6 + n]; + } + + rxCc2500SpiConfigMutable()->rxNum = packet[12]; + + return true; + } + } + } + } + } + + return false; +} + +static bool getBind2(uint8_t *packet) +{ + if (bindIdx <= 120) { + if (cc2500getGdo()) { + uint8_t ccLen = cc2500ReadReg(CC2500_3B_RXBYTES | CC2500_READ_BURST) & 0x7F; + if (ccLen) { + cc2500ReadFifo(packet, ccLen); + if (packet[ccLen - 1] & 0x80) { + if (packet[2] == 0x01) { + if ((packet[3] == rxCc2500SpiConfig()->bindTxId[0]) && + (packet[4] == rxCc2500SpiConfig()->bindTxId[1])) { + if (packet[5] == bindIdx) { +#if defined(DJTS) + if (packet[5] == 0x2D) { + for (uint8_t i = 0; i < 2; i++) { + rxCc2500SpiConfigMutable()->bindHopData[packet[5] + i] = packet[6 + i]; + } + listLength = 47; + + return true; + } +#endif + + for (uint8_t n = 0; n < 5; n++) { + if (packet[6 + n] == packet[ccLen - 3] || (packet[6 + n] == 0)) { + if (bindIdx >= 0x2D) { + listLength = packet[5] + n; + + return true; + } + } + + rxCc2500SpiConfigMutable()->bindHopData[packet[5] + n] = packet[6 + n]; + } + + bindIdx = bindIdx + 5; + + return false; + } + } + } + } + } + } + + return false; + } else { + return true; + } +} + +rx_spi_received_e frSkySpiDataReceived(uint8_t *packet) +{ + rx_spi_received_e ret = RX_SPI_RECEIVED_NONE; + + switch (protocolState) { + case STATE_INIT: + if ((millis() - start_time) > 10) { + initialise(); + + protocolState = STATE_BIND; + } + + break; + case STATE_BIND: + if (rxSpiCheckBindRequested(true) || rxCc2500SpiConfig()->autoBind) { + rxSpiLedOn(); + initTuneRx(); + + protocolState = STATE_BIND_TUNING; + } else { + protocolState = STATE_STARTING; + } + + break; + case STATE_BIND_TUNING: + if (tuneRx(packet)) { + initGetBind(); + initialiseData(true); + + protocolState = STATE_BIND_BINDING1; + } + + break; + case STATE_BIND_BINDING1: + if (getBind1(packet)) { + protocolState = STATE_BIND_BINDING2; + } + + break; + case STATE_BIND_BINDING2: + if (getBind2(packet)) { + cc2500Strobe(CC2500_SIDLE); + + protocolState = STATE_BIND_COMPLETE; + } + + break; + case STATE_BIND_COMPLETE: + if (!rxCc2500SpiConfig()->autoBind) { + writeEEPROM(); + } else { + uint8_t ctr = 80; + while (ctr--) { + rxSpiLedToggle(); + delay(50); + } + } + + ret = RX_SPI_RECEIVED_BIND; + protocolState = STATE_STARTING; + + break; + default: + ret = handlePacket(packet, &protocolState); + + break; + } + + return ret; +} + +rx_spi_received_e frSkySpiProcessFrame(uint8_t *packet) +{ + if (processFrame) { + return processFrame(packet); + } + + return RX_SPI_RECEIVED_NONE; +} + +void frSkySpiSetRcData(uint16_t *rcData, const uint8_t *payload) +{ + setRcData(rcData, payload); +} + +void nextChannel(uint8_t skip) +{ + static uint8_t channr = 0; + + channr += skip; + while (channr >= listLength) { + channr -= listLength; + } + cc2500Strobe(CC2500_SIDLE); + cc2500WriteReg(CC2500_23_FSCAL3, + calData[rxCc2500SpiConfig()->bindHopData[channr]][0]); + cc2500WriteReg(CC2500_24_FSCAL2, + calData[rxCc2500SpiConfig()->bindHopData[channr]][1]); + cc2500WriteReg(CC2500_25_FSCAL1, + calData[rxCc2500SpiConfig()->bindHopData[channr]][2]); + cc2500WriteReg(CC2500_0A_CHANNR, rxCc2500SpiConfig()->bindHopData[channr]); + if (spiProtocol == RX_SPI_FRSKY_D) { + cc2500Strobe(CC2500_SFRX); + } +} + +bool frSkySpiInit(const rxSpiConfig_t *rxSpiConfig, rxRuntimeConfig_t *rxRuntimeConfig) +{ + rxSpiCommonIOInit(rxSpiConfig); + if (!cc2500SpiInit()) { + return false; + } + + spiProtocol = rxSpiConfig->rx_spi_protocol; + + switch (spiProtocol) { + case RX_SPI_FRSKY_D: + rxRuntimeConfig->channelCount = RC_CHANNEL_COUNT_FRSKY_D; + + handlePacket = frSkyDHandlePacket; + setRcData = frSkyDSetRcData; + frSkyDInit(); + + break; + case RX_SPI_FRSKY_X: + case RX_SPI_FRSKY_X_LBT: + rxRuntimeConfig->channelCount = RC_CHANNEL_COUNT_FRSKY_X; + + handlePacket = frSkyXHandlePacket; +#if defined(USE_RX_FRSKY_SPI_TELEMETRY) && defined(USE_TELEMETRY_SMARTPORT) + processFrame = frSkyXProcessFrame; +#endif + setRcData = frSkyXSetRcData; + frSkyXInit(spiProtocol); + + break; + default: + + break; + } + +#if defined(USE_RX_FRSKY_SPI_TELEMETRY) + if (rssiSource == RSSI_SOURCE_NONE) { + rssiSource = RSSI_SOURCE_RX_PROTOCOL; + } +#endif + + missingPackets = 0; + timeoutUs = 50; + + start_time = millis(); + protocolState = STATE_INIT; + + return true; +} +#endif diff --git a/sw/airborne/subsystems/radio_control/cc2500_frsky/cc2500_frsky_shared.h b/sw/airborne/subsystems/radio_control/cc2500_frsky/cc2500_frsky_shared.h new file mode 100644 index 0000000000..24a49c0f0a --- /dev/null +++ b/sw/airborne/subsystems/radio_control/cc2500_frsky/cc2500_frsky_shared.h @@ -0,0 +1,57 @@ +// betaflight/src/main/rx/cc2500_frsky_shared.h @ cb66ee0 +/* + * This file is part of Cleanflight and Betaflight. + * + * Cleanflight and Betaflight are free software. You can redistribute + * this software and/or modify this software under the terms of the + * GNU General Public License as published by the Free Software + * Foundation, either version 3 of the License, or (at your option) + * any later version. + * + * Cleanflight and Betaflight are distributed in the hope that they + * will be useful, but WITHOUT ANY WARRANTY; without even the implied + * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + * See the GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this software. + * + * If not, see . + */ + +#pragma once + +//#include "rx/rx_spi.h" + +#define MAX_MISSING_PKT 100 + +#define DEBUG_DATA_ERROR_COUNT 0 +#define DEBUG_DATA_MISSING_PACKETS 1 +#define DEBUG_DATA_BAD_FRAME 2 + + +#define SYNC_DELAY_MAX 9000 + +#define MAX_MISSING_PKT 100 + +enum { + STATE_INIT = 0, + STATE_BIND, + STATE_BIND_TUNING, + STATE_BIND_BINDING1, + STATE_BIND_BINDING2, + STATE_BIND_COMPLETE, + STATE_STARTING, + STATE_UPDATE, + STATE_DATA, + STATE_TELEMETRY, + STATE_RESUME, +}; + +extern uint8_t listLength; +extern uint32_t missingPackets; +extern timeDelta_t timeoutUs; + +void initialiseData(bool inBindState); + +void nextChannel(uint8_t skip); diff --git a/sw/airborne/subsystems/radio_control/cc2500_frsky/cc2500_frsky_x.c b/sw/airborne/subsystems/radio_control/cc2500_frsky/cc2500_frsky_x.c new file mode 100644 index 0000000000..137e7d87af --- /dev/null +++ b/sw/airborne/subsystems/radio_control/cc2500_frsky/cc2500_frsky_x.c @@ -0,0 +1,603 @@ +#include "cc2500_compat.h" + +#include "peripherals/cc2500.h" +#include "cc2500_settings.h" +#include "cc2500_rx_spi_common.h" +#include "cc2500_common.h" +#include "cc2500_frsky_common.h" +#include "cc2500_frsky_shared.h" +#include "cc2500_frsky_x.h" +#include "cc2500_smartport.h" + +#define UNUSED(x) (void)(x) + +// betaflight/src/main/rx/cc2500_frsky_x.c @ e78f976 +/* + * This file is part of Cleanflight and Betaflight. + * + * Cleanflight and Betaflight are free software. You can redistribute + * this software and/or modify this software under the terms of the + * GNU General Public License as published by the Free Software + * Foundation, either version 3 of the License, or (at your option) + * any later version. + * + * Cleanflight and Betaflight are distributed in the hope that they + * will be useful, but WITHOUT ANY WARRANTY; without even the implied + * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + * See the GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this software. + * + * If not, see . + */ + +#include + +//#include "platform.h" + +#ifdef USE_RX_FRSKY_SPI_X + +//#include "build/build_config.h" +//#include "build/debug.h" +// +//#include "common/maths.h" +//#include "common/utils.h" +// +//#include "config/feature.h" +// +//#include "drivers/adc.h" +//#include "drivers/rx/rx_cc2500.h" +//#include "drivers/io.h" +//#include "drivers/io_def.h" +//#include "drivers/io_types.h" +//#include "drivers/resource.h" +//#include "drivers/system.h" +//#include "drivers/time.h" +// +//#include "fc/config.h" +// +//#include "pg/rx.h" +//#include "pg/rx_spi.h" +//#include "pg/rx_spi_cc2500.h" +// +//#include "rx/rx_spi_common.h" +//#include "rx/cc2500_common.h" +//#include "rx/cc2500_frsky_common.h" +//#include "rx/cc2500_frsky_shared.h" +// +//#include "sensors/battery.h" +// +//#include "telemetry/smartport.h" +// +//#include "cc2500_frsky_x.h" + +const uint16_t crcTable[] = { + 0x0000,0x1189,0x2312,0x329b,0x4624,0x57ad,0x6536,0x74bf, + 0x8c48,0x9dc1,0xaf5a,0xbed3,0xca6c,0xdbe5,0xe97e,0xf8f7, + 0x1081,0x0108,0x3393,0x221a,0x56a5,0x472c,0x75b7,0x643e, + 0x9cc9,0x8d40,0xbfdb,0xae52,0xdaed,0xcb64,0xf9ff,0xe876, + 0x2102,0x308b,0x0210,0x1399,0x6726,0x76af,0x4434,0x55bd, + 0xad4a,0xbcc3,0x8e58,0x9fd1,0xeb6e,0xfae7,0xc87c,0xd9f5, + 0x3183,0x200a,0x1291,0x0318,0x77a7,0x662e,0x54b5,0x453c, + 0xbdcb,0xac42,0x9ed9,0x8f50,0xfbef,0xea66,0xd8fd,0xc974, + 0x4204,0x538d,0x6116,0x709f,0x0420,0x15a9,0x2732,0x36bb, + 0xce4c,0xdfc5,0xed5e,0xfcd7,0x8868,0x99e1,0xab7a,0xbaf3, + 0x5285,0x430c,0x7197,0x601e,0x14a1,0x0528,0x37b3,0x263a, + 0xdecd,0xcf44,0xfddf,0xec56,0x98e9,0x8960,0xbbfb,0xaa72, + 0x6306,0x728f,0x4014,0x519d,0x2522,0x34ab,0x0630,0x17b9, + 0xef4e,0xfec7,0xcc5c,0xddd5,0xa96a,0xb8e3,0x8a78,0x9bf1, + 0x7387,0x620e,0x5095,0x411c,0x35a3,0x242a,0x16b1,0x0738, + 0xffcf,0xee46,0xdcdd,0xcd54,0xb9eb,0xa862,0x9af9,0x8b70, + 0x8408,0x9581,0xa71a,0xb693,0xc22c,0xd3a5,0xe13e,0xf0b7, + 0x0840,0x19c9,0x2b52,0x3adb,0x4e64,0x5fed,0x6d76,0x7cff, + 0x9489,0x8500,0xb79b,0xa612,0xd2ad,0xc324,0xf1bf,0xe036, + 0x18c1,0x0948,0x3bd3,0x2a5a,0x5ee5,0x4f6c,0x7df7,0x6c7e, + 0xa50a,0xb483,0x8618,0x9791,0xe32e,0xf2a7,0xc03c,0xd1b5, + 0x2942,0x38cb,0x0a50,0x1bd9,0x6f66,0x7eef,0x4c74,0x5dfd, + 0xb58b,0xa402,0x9699,0x8710,0xf3af,0xe226,0xd0bd,0xc134, + 0x39c3,0x284a,0x1ad1,0x0b58,0x7fe7,0x6e6e,0x5cf5,0x4d7c, + 0xc60c,0xd785,0xe51e,0xf497,0x8028,0x91a1,0xa33a,0xb2b3, + 0x4a44,0x5bcd,0x6956,0x78df,0x0c60,0x1de9,0x2f72,0x3efb, + 0xd68d,0xc704,0xf59f,0xe416,0x90a9,0x8120,0xb3bb,0xa232, + 0x5ac5,0x4b4c,0x79d7,0x685e,0x1ce1,0x0d68,0x3ff3,0x2e7a, + 0xe70e,0xf687,0xc41c,0xd595,0xa12a,0xb0a3,0x8238,0x93b1, + 0x6b46,0x7acf,0x4854,0x59dd,0x2d62,0x3ceb,0x0e70,0x1ff9, + 0xf78f,0xe606,0xd49d,0xc514,0xb1ab,0xa022,0x92b9,0x8330, + 0x7bc7,0x6a4e,0x58d5,0x495c,0x3de3,0x2c6a,0x1ef1,0x0f78 +}; + +#define TELEMETRY_OUT_BUFFER_SIZE 64 + +#define TELEMETRY_SEQUENCE_LENGTH 4 + +#define A1_CONST_X 50 + +typedef struct telemetrySequenceMarkerData_s { + unsigned int packetSequenceId: 2; + unsigned int unused: 1; + unsigned int initRequest: 1; + unsigned int ackSequenceId: 2; + unsigned int retransmissionRequested: 1; + unsigned int initResponse: 1; +} __attribute__ ((__packed__)) telemetrySequenceMarkerData_t; + +typedef union telemetrySequenceMarker_s { + uint8_t raw; + telemetrySequenceMarkerData_t data; +} __attribute__ ((__packed__)) telemetrySequenceMarker_t; + +#define SEQUENCE_MARKER_REMOTE_PART 0xf0 + +#define TELEMETRY_DATA_SIZE 5 + +typedef struct telemetryData_s { + uint8_t dataLength; + uint8_t data[TELEMETRY_DATA_SIZE]; +} __attribute__ ((__packed__)) telemetryData_t; + +typedef struct telemetryBuffer_s { + telemetryData_t data; + uint8_t needsProcessing; +} telemetryBuffer_t; + +#define TELEMETRY_FRAME_SIZE sizeof(telemetryData_t) + +typedef struct telemetryPayload_s { + uint8_t packetConst; + uint8_t rssiA1; + telemetrySequenceMarker_t sequence; + telemetryData_t data; + uint8_t crc[2]; +} __attribute__ ((__packed__)) telemetryPayload_t; + +#if defined(USE_RX_FRSKY_SPI_TELEMETRY) +static telemetryData_t telemetryTxBuffer[TELEMETRY_SEQUENCE_LENGTH]; +#endif + +static telemetryBuffer_t telemetryRxBuffer[TELEMETRY_SEQUENCE_LENGTH]; + +static telemetrySequenceMarker_t responseToSend; + +#if defined(USE_RX_FRSKY_SPI_TELEMETRY) +static uint8_t frame[20]; + +#if defined(USE_TELEMETRY_SMARTPORT) +static uint8_t telemetryOutWriter; + +static uint8_t telemetryOutBuffer[TELEMETRY_OUT_BUFFER_SIZE]; + +static bool telemetryEnabled = false; + +static uint8_t remoteToProcessId = 0; +static uint8_t remoteToProcessIndex = 0; +#endif +#endif // USE_RX_FRSKY_SPI_TELEMETRY + +static uint8_t packetLength; +static uint16_t telemetryDelayUs; + +static uint16_t calculateCrc(const uint8_t *data, uint8_t len) { + uint16_t crc = 0; + for (unsigned i = 0; i < len; i++) { + crc = (crc << 8) ^ (crcTable[((uint8_t)(crc >> 8) ^ *data++) & 0xFF]); + } + return crc; +} + +#if defined(USE_RX_FRSKY_SPI_TELEMETRY) +#if defined(USE_TELEMETRY_SMARTPORT) +static uint8_t appendSmartPortData(uint8_t *buf) +{ + static uint8_t telemetryOutReader = 0; + + uint8_t index; + for (index = 0; index < TELEMETRY_DATA_SIZE; index++) { // max 5 bytes in a frame + if (telemetryOutReader == telemetryOutWriter){ // no new data + break; + } + buf[index] = telemetryOutBuffer[telemetryOutReader]; + telemetryOutReader = (telemetryOutReader + 1) % TELEMETRY_OUT_BUFFER_SIZE; + } + + return index; +} +#endif + +static void buildTelemetryFrame(uint8_t *packet) +{ + static uint8_t localPacketId; + + static bool evenRun = false; + + frame[0] = 0x0E;//length + frame[1] = rxCc2500SpiConfig()->bindTxId[0]; + frame[2] = rxCc2500SpiConfig()->bindTxId[1]; + frame[3] = packet[3]; + + if (evenRun) { + frame[4] = (uint8_t)cc2500getRssiDbm() | 0x80; + } else { + uint8_t a1Value; + switch (rxCc2500SpiConfig()->a1Source) { + case FRSKY_SPI_A1_SOURCE_VBAT: + a1Value = getLegacyBatteryVoltage() & 0x7f; + break; + case FRSKY_SPI_A1_SOURCE_EXTADC: + a1Value = (uint8_t)((adcGetChannel(ADC_EXTERNAL1) & 0xfe0) >> 5); + break; + case FRSKY_SPI_A1_SOURCE_CONST: + a1Value = A1_CONST_X & 0x7f; + break; + } + frame[4] = a1Value; + } + evenRun = !evenRun; + + telemetrySequenceMarker_t *inFrameMarker = (telemetrySequenceMarker_t *)&packet[21]; + telemetrySequenceMarker_t *outFrameMarker = (telemetrySequenceMarker_t *)&frame[5]; + if (inFrameMarker->data.initRequest) { // check syncronization at startup ok if not no sport telemetry + outFrameMarker-> raw = 0; + outFrameMarker->data.initRequest = 1; + outFrameMarker->data.initResponse = 1; + + localPacketId = 0; + } else { + if (inFrameMarker->data.retransmissionRequested) { + uint8_t retransmissionFrameId = inFrameMarker->data.ackSequenceId; + outFrameMarker->raw = responseToSend.raw & SEQUENCE_MARKER_REMOTE_PART; + outFrameMarker->data.packetSequenceId = retransmissionFrameId; + + memcpy(&frame[6], &telemetryTxBuffer[retransmissionFrameId], TELEMETRY_FRAME_SIZE); + } else { + uint8_t localAckId = inFrameMarker->data.ackSequenceId; + if (localPacketId != (localAckId + 1) % TELEMETRY_SEQUENCE_LENGTH) { + outFrameMarker->raw = responseToSend.raw & SEQUENCE_MARKER_REMOTE_PART; + outFrameMarker->data.packetSequenceId = localPacketId; + + frame[6] = appendSmartPortData(&frame[7]); + memcpy(&telemetryTxBuffer[localPacketId], &frame[6], TELEMETRY_FRAME_SIZE); + + localPacketId = (localPacketId + 1) % TELEMETRY_SEQUENCE_LENGTH; + } + } + } + + uint16_t lcrc = calculateCrc(&frame[3], 10); + frame[13]=lcrc>>8; + frame[14]=lcrc; +} + +static bool frSkyXCheckQueueEmpty(void) +{ + return true; +} + +#if defined(USE_TELEMETRY_SMARTPORT) +static void frSkyXTelemetrySendByte(uint8_t c) { + if (c == FSSP_DLE || c == FSSP_START_STOP) { + telemetryOutBuffer[telemetryOutWriter] = FSSP_DLE; + telemetryOutWriter = (telemetryOutWriter + 1) % TELEMETRY_OUT_BUFFER_SIZE; + telemetryOutBuffer[telemetryOutWriter] = c ^ FSSP_DLE_XOR; + telemetryOutWriter = (telemetryOutWriter + 1) % TELEMETRY_OUT_BUFFER_SIZE; + } else { + telemetryOutBuffer[telemetryOutWriter] = c; + telemetryOutWriter = (telemetryOutWriter + 1) % TELEMETRY_OUT_BUFFER_SIZE; + } +} + +static void frSkyXTelemetryWriteFrame(const smartPortPayload_t *payload) +{ + telemetryOutBuffer[telemetryOutWriter] = FSSP_START_STOP; + telemetryOutWriter = (telemetryOutWriter + 1) % TELEMETRY_OUT_BUFFER_SIZE; + telemetryOutBuffer[telemetryOutWriter] = FSSP_SENSOR_ID1 & 0x1f; + telemetryOutWriter = (telemetryOutWriter + 1) % TELEMETRY_OUT_BUFFER_SIZE; + uint8_t *data = (uint8_t *)payload; + for (unsigned i = 0; i < sizeof(smartPortPayload_t); i++) { + frSkyXTelemetrySendByte(*data++); + } +} +#endif +#endif // USE_RX_FRSKY_SPI_TELEMETRY + + +void frSkyXSetRcData(uint16_t *rcData, const uint8_t *packet) +{ + uint16_t c[8]; + // ignore failsafe packet + if (packet[7] != 0) { + return; + } + c[0] = (uint16_t)((packet[10] << 8) & 0xF00) | packet[9]; + c[1] = (uint16_t)((packet[11] << 4) & 0xFF0) | (packet[10] >> 4); + c[2] = (uint16_t)((packet[13] << 8) & 0xF00) | packet[12]; + c[3] = (uint16_t)((packet[14] << 4) & 0xFF0) | (packet[13] >> 4); + c[4] = (uint16_t)((packet[16] << 8) & 0xF00) | packet[15]; + c[5] = (uint16_t)((packet[17] << 4) & 0xFF0) | (packet[16] >> 4); + c[6] = (uint16_t)((packet[19] << 8) & 0xF00) | packet[18]; + c[7] = (uint16_t)((packet[20] << 4) & 0xFF0) | (packet[19] >> 4); + + for (unsigned i = 0; i < 8; i++) { + const bool channelIsShifted = c[i] & 0x800; + const uint16_t channelValue = c[i] & 0x7FF; + rcData[channelIsShifted ? i + 8 : i] = ((channelValue - 64) * 2 + 860 * 3) / 3; + } +} + +bool isValidPacket(const uint8_t *packet) +{ + uint16_t lcrc = calculateCrc(&packet[3], (packetLength - 7)); + if ((lcrc >> 8) == packet[packetLength - 4] && (lcrc & 0x00FF) == packet[packetLength - 3] && + (packet[0] == packetLength - 3) && + (packet[1] == rxCc2500SpiConfig()->bindTxId[0]) && + (packet[2] == rxCc2500SpiConfig()->bindTxId[1]) && + (rxCc2500SpiConfig()->rxNum == 0 || packet[6] == 0 || packet[6] == rxCc2500SpiConfig()->rxNum)) { + return true; + } + return false; +} + +rx_spi_received_e frSkyXHandlePacket(uint8_t * const packet, uint8_t * const protocolState) +{ + static unsigned receiveTelemetryRetryCount = 0; + static bool skipChannels = true; + + static uint8_t remoteAckId = 0; + + static timeUs_t packetTimerUs; + + static bool frameReceived; + static timeDelta_t receiveDelayUs; + static uint8_t channelsToSkip = 1; + static uint32_t packetErrors = 0; + +#if defined(USE_RX_FRSKY_SPI_TELEMETRY) + static bool telemetryReceived = false; +#endif + + rx_spi_received_e ret = RX_SPI_RECEIVED_NONE; + + switch (*protocolState) { + case STATE_STARTING: + listLength = 47; + initialiseData(false); + *protocolState = STATE_UPDATE; + nextChannel(1); + cc2500Strobe(CC2500_SRX); + break; + case STATE_UPDATE: + packetTimerUs = micros(); + *protocolState = STATE_DATA; + frameReceived = false; // again set for receive + receiveDelayUs = 5300; + if (rxSpiCheckBindRequested(false)) { + packetTimerUs = 0; + timeoutUs = 50; + missingPackets = 0; + *protocolState = STATE_INIT; + + break; + } + + FALLTHROUGH; + // here FS code could be + case STATE_DATA: + if (cc2500getGdo() && (frameReceived == false)){ + uint8_t ccLen = cc2500ReadReg(CC2500_3B_RXBYTES | CC2500_READ_BURST) & 0x7F; + if (ccLen >= packetLength) { + cc2500ReadFifo(packet, packetLength); + if (isValidPacket(packet)) { + missingPackets = 0; + timeoutUs = 1; + receiveDelayUs = 0; + rxSpiLedOn(); + if (skipChannels) { + channelsToSkip = packet[5] << 2; + if (packet[4] >= listLength) { + if (packet[4] < (64 + listLength)) { + channelsToSkip += 1; + } else if (packet[4] < (128 + listLength)) { + channelsToSkip += 2; + } else if (packet[4] < (192 + listLength)) { + channelsToSkip += 3; + } + } + telemetryReceived = true; // now telemetry can be sent + skipChannels = false; + } + cc2500setRssiDbm(packet[packetLength - 2]); + + telemetrySequenceMarker_t *inFrameMarker = (telemetrySequenceMarker_t *)&packet[21]; + + uint8_t remoteNewPacketId = inFrameMarker->data.packetSequenceId; + memcpy(&telemetryRxBuffer[remoteNewPacketId].data, &packet[22], TELEMETRY_FRAME_SIZE); + telemetryRxBuffer[remoteNewPacketId].needsProcessing = true; + + responseToSend.raw = 0; + uint8_t remoteToAckId = (remoteAckId + 1) % TELEMETRY_SEQUENCE_LENGTH; + if (remoteNewPacketId != remoteToAckId) { + while (remoteToAckId != remoteNewPacketId) { + if (!telemetryRxBuffer[remoteToAckId].needsProcessing) { + responseToSend.data.ackSequenceId = remoteToAckId; + responseToSend.data.retransmissionRequested = 1; + + receiveTelemetryRetryCount++; + + break; + } + + remoteToAckId = (remoteToAckId + 1) % TELEMETRY_SEQUENCE_LENGTH; + } + } + + if (!responseToSend.data.retransmissionRequested) { + receiveTelemetryRetryCount = 0; + + remoteToAckId = (remoteAckId + 1) % TELEMETRY_SEQUENCE_LENGTH; + uint8_t remoteNextAckId = remoteToAckId; + while (telemetryRxBuffer[remoteToAckId].needsProcessing && remoteToAckId != remoteAckId) { + remoteNextAckId = remoteToAckId; + remoteToAckId = (remoteToAckId + 1) % TELEMETRY_SEQUENCE_LENGTH; + } + remoteAckId = remoteNextAckId; + responseToSend.data.ackSequenceId = remoteAckId; + } + + if (receiveTelemetryRetryCount >= 5) { +#if defined(USE_RX_FRSKY_SPI_TELEMETRY) && defined(USE_TELEMETRY_SMARTPORT) + remoteToProcessId = 0; + remoteToProcessIndex = 0; +#endif + remoteAckId = TELEMETRY_SEQUENCE_LENGTH - 1; + for (unsigned i = 0; i < TELEMETRY_SEQUENCE_LENGTH; i++) { + telemetryRxBuffer[i].needsProcessing = false; + } + + receiveTelemetryRetryCount = 0; + } + + packetTimerUs = micros(); + frameReceived = true; // no need to process frame again. + } + if (!frameReceived) { + packetErrors++; + DEBUG_SET(DEBUG_RX_FRSKY_SPI, DEBUG_DATA_BAD_FRAME, packetErrors); + cc2500Strobe(CC2500_SFRX); + } + } + } + if (telemetryReceived) { + if (cmpTimeUs(micros(), packetTimerUs) > receiveDelayUs) { // if received or not received in this time sent telemetry data + *protocolState = STATE_TELEMETRY; + buildTelemetryFrame(packet); + } + } + if (cmpTimeUs(micros(), packetTimerUs) > timeoutUs * SYNC_DELAY_MAX) { + rxSpiLedToggle(); + + setRssiDirect(0, RSSI_SOURCE_RX_PROTOCOL); + nextChannel(1); + cc2500Strobe(CC2500_SRX); + *protocolState = STATE_UPDATE; + } + if (frameReceived) { + ret |= RX_SPI_RECEIVED_DATA; + } + + break; +#ifdef USE_RX_FRSKY_SPI_TELEMETRY + case STATE_TELEMETRY: + if (cmpTimeUs(micros(), packetTimerUs) >= receiveDelayUs + telemetryDelayUs) { // if received or not received in this time sent telemetry data + cc2500Strobe(CC2500_SIDLE); + cc2500SetPower(6); + cc2500Strobe(CC2500_SFRX); + delayMicroseconds(30); +#if defined(USE_RX_CC2500_SPI_PA_LNA) + cc2500TxEnable(); +#endif + cc2500Strobe(CC2500_SIDLE); + cc2500WriteFifo(frame, frame[0] + 1); + +#if defined(USE_TELEMETRY_SMARTPORT) + if (telemetryEnabled) { + ret |= RX_SPI_ROCESSING_REQUIRED; + } +#endif + *protocolState = STATE_RESUME; + } + + break; +#endif // USE_RX_FRSKY_SPI_TELEMETRY + case STATE_RESUME: + if (cmpTimeUs(micros(), packetTimerUs) > receiveDelayUs + 3700) { + packetTimerUs = micros(); + receiveDelayUs = 5300; + frameReceived = false; // again set for receive + nextChannel(channelsToSkip); + cc2500Strobe(CC2500_SRX); +#ifdef USE_RX_CC2500_SPI_PA_LNA + cc2500TxDisable(); +#if defined(USE_RX_CC2500_SPI_DIVERSITY) + if (missingPackets >= 2) { + cc2500switchAntennae(); + } +#endif +#endif // USE_RX_CC2500_SPI_PA_LNA + if (missingPackets > MAX_MISSING_PKT) { + timeoutUs = 50; + skipChannels = true; + telemetryReceived = false; + *protocolState = STATE_UPDATE; + break; + } + missingPackets++; + DEBUG_SET(DEBUG_RX_FRSKY_SPI, DEBUG_DATA_MISSING_PACKETS, missingPackets); + *protocolState = STATE_DATA; + } + break; + } + + return ret; +} + +#if defined(USE_RX_FRSKY_SPI_TELEMETRY) && defined(USE_TELEMETRY_SMARTPORT) +rx_spi_received_e frSkyXProcessFrame(uint8_t * const packet) +{ + static timeMs_t pollingTimeMs = 0; + + UNUSED(packet); + + bool clearToSend = false; + timeMs_t now = millis(); + smartPortPayload_t *payload = NULL; + if ((now - pollingTimeMs) > 24) { + pollingTimeMs = now; + + clearToSend = true; + } else { + while (telemetryRxBuffer[remoteToProcessId].needsProcessing && !payload) { + if (remoteToProcessIndex >= telemetryRxBuffer[remoteToProcessId].data.dataLength) { + remoteToProcessIndex = 0; + telemetryRxBuffer[remoteToProcessId].needsProcessing = false; + remoteToProcessId = (remoteToProcessId + 1) % TELEMETRY_SEQUENCE_LENGTH; + + if (!telemetryRxBuffer[remoteToProcessId].needsProcessing) { + break; + } + } + + while (remoteToProcessIndex < telemetryRxBuffer[remoteToProcessId].data.dataLength && !payload) { + payload = smartPortDataReceive(telemetryRxBuffer[remoteToProcessId].data.data[remoteToProcessIndex], &clearToSend, frSkyXCheckQueueEmpty, false); + remoteToProcessIndex = remoteToProcessIndex + 1; + } + } + } + + processSmartPortTelemetry(payload, &clearToSend, NULL); + + return RX_SPI_RECEIVED_NONE; +} +#endif + +void frSkyXInit(const rx_spi_protocol_e spiProtocol) +{ + switch(spiProtocol) { + case RX_SPI_FRSKY_X: + packetLength = 32; + telemetryDelayUs = 400; + break; + case RX_SPI_FRSKY_X_LBT: + packetLength = 35; + telemetryDelayUs = 1400; + break; + default: + break; + } +#if defined(USE_TELEMETRY_SMARTPORT) + if (featureIsEnabled(FEATURE_TELEMETRY)) { + telemetryEnabled = initSmartPortTelemetryExternal(frSkyXTelemetryWriteFrame); + } +#endif +} + +#endif diff --git a/sw/airborne/subsystems/radio_control/cc2500_frsky/cc2500_frsky_x.h b/sw/airborne/subsystems/radio_control/cc2500_frsky/cc2500_frsky_x.h new file mode 100644 index 0000000000..0cc9cf80c0 --- /dev/null +++ b/sw/airborne/subsystems/radio_control/cc2500_frsky/cc2500_frsky_x.h @@ -0,0 +1,35 @@ +#include "cc2500_compat.h" + +// betaflight/src/main/rx/cc2500_frsky_x.h @ 766c90b +/* + * This file is part of Cleanflight and Betaflight. + * + * Cleanflight and Betaflight are free software. You can redistribute + * this software and/or modify this software under the terms of the + * GNU General Public License as published by the Free Software + * Foundation, either version 3 of the License, or (at your option) + * any later version. + * + * Cleanflight and Betaflight are distributed in the hope that they + * will be useful, but WITHOUT ANY WARRANTY; without even the implied + * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + * See the GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this software. + * + * If not, see . + */ + +#pragma once + +//#include "rx/rx.h" +//#include "rx/rx_spi.h" + +#define RC_CHANNEL_COUNT_FRSKY_X 16 + +void frSkyXSetRcData(uint16_t *rcData, const uint8_t *payload); + +void frSkyXInit(const rx_spi_protocol_e spiProtocol); +rx_spi_received_e frSkyXHandlePacket(uint8_t * const packet, uint8_t * const protocolState); +rx_spi_received_e frSkyXProcessFrame(uint8_t * const packet); diff --git a/sw/airborne/subsystems/radio_control/cc2500_frsky/cc2500_paparazzi.c b/sw/airborne/subsystems/radio_control/cc2500_frsky/cc2500_paparazzi.c new file mode 100644 index 0000000000..0973c041f6 --- /dev/null +++ b/sw/airborne/subsystems/radio_control/cc2500_frsky/cc2500_paparazzi.c @@ -0,0 +1,77 @@ +/* + * Copyright (C) 2019 Tom van Dijk + * + * This file is part of paparazzi. + * + * paparazzi 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 2, or (at your option) + * any later version. + * + * paparazzi 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 paparazzi; see the file COPYING. If not, write to + * the Free Software Foundation, 59 Temple Place - Suite 330, + * Boston, MA 02111-1307, USA. + */ + +#include "cc2500_paparazzi.h" + +#include "subsystems/radio_control.h" +#include "peripherals/cc2500.h" +#include "cc2500_common.h" +#include "cc2500_frsky_common.h" +#include "cc2500_settings.h" +#include "cc2500_rx.h" + +#include + + +static uint16_t frsky_raw[RADIO_CTL_NB]; + + +#if PERIODIC_TELEMETRY +#include "subsystems/datalink/telemetry.h" + +static void send_cc2500_ppm(struct transport_tx *trans, struct link_device *dev) +{ + pprz_msg_send_PPM(trans, dev, AC_ID, + &radio_control.frame_rate, + (sizeof(frsky_raw) / sizeof(frsky_raw[0])), + frsky_raw); +} +#endif + + +void radio_control_impl_init(void) { + cc2500_settings_init(); + cc2500_init(); + cc2500Reset(); + rxInit(); +#if PERIODIC_TELEMETRY + register_periodic_telemetry(DefaultPeriodic, PPRZ_MSG_ID_PPM, send_cc2500_ppm); +#endif +} + + +void radio_control_impl_event(void (* _received_frame_handler)(void)) { + if (rxRuntimeConfig.rcFrameStatusFn(&rxRuntimeConfig) & RX_FRAME_COMPLETE) { + rxRuntimeConfig.rcProcessFrameFn(&rxRuntimeConfig); + radio_control.frame_cpt++; + radio_control.time_since_last_frame = 0; + if (radio_control.radio_ok_cpt > 0) { + radio_control.radio_ok_cpt--; + } else { + radio_control.status = RC_OK; + for (int i = 0; i < RADIO_CONTROL_NB_CHANNEL; ++i) { + frsky_raw[i] = rxRuntimeConfig.rcReadRawFn(&rxRuntimeConfig, i); + } + NormalizePpmIIR(frsky_raw, radio_control); + _received_frame_handler(); + } + } +} diff --git a/sw/airborne/subsystems/radio_control/cc2500_frsky/cc2500_paparazzi.h b/sw/airborne/subsystems/radio_control/cc2500_frsky/cc2500_paparazzi.h new file mode 100644 index 0000000000..5d8e400454 --- /dev/null +++ b/sw/airborne/subsystems/radio_control/cc2500_frsky/cc2500_paparazzi.h @@ -0,0 +1,40 @@ +/* + * Copyright (C) 2019 Tom van Dijk + * + * This file is part of paparazzi. + * + * paparazzi 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 2, or (at your option) + * any later version. + * + * paparazzi 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 paparazzi; see the file COPYING. If not, write to + * the Free Software Foundation, 59 Temple Place - Suite 330, + * Boston, MA 02111-1307, USA. + */ + +#ifndef RADIO_CONTROL_CC2500_PAPARAZZI_H +#define RADIO_CONTROL_CC2500_PAPARAZZI_H + +#define RC_PPM_TICKS_OF_USEC(_x) (_x) +#define RC_PPM_SIGNED_TICKS_OF_USEC(_x) (_x) +#define USEC_OF_RC_PPM_TICKS(_x) (_x) + +#include "generated/airframe.h" +#include "generated/radio.h" + +#ifndef RADIO_CONTROL_NB_CHANNEL +#define RADIO_CONTROL_NB_CHANNEL RADIO_CTL_NB +#endif + +extern void radio_control_impl_event(void (* _received_frame_handler)(void)); +#define RadioControlEvent(_received_frame_handler) radio_control_impl_event(_received_frame_handler) + + +#endif // RADIO_CONTROL_CC2500_PAPARAZZI_H diff --git a/sw/airborne/subsystems/radio_control/cc2500_frsky/cc2500_rx.c b/sw/airborne/subsystems/radio_control/cc2500_frsky/cc2500_rx.c new file mode 100644 index 0000000000..7a632ea010 --- /dev/null +++ b/sw/airborne/subsystems/radio_control/cc2500_frsky/cc2500_rx.c @@ -0,0 +1,874 @@ +#include "cc2500_compat.h" + +#include "cc2500_rx.h" +#include "cc2500_rx_spi.h" +#include "cc2500_settings.h" + +#define UNUSED(x) (void)(x) + +// CAUTION: LARGE PARTS OF THIS FILE ARE COMMENTED OUT! +// betaflight/src/main/rx/rx.c @ 4e8249e +/* + * This file is part of Cleanflight and Betaflight. + * + * Cleanflight and Betaflight are free software. You can redistribute + * this software and/or modify this software under the terms of the + * GNU General Public License as published by the Free Software + * Foundation, either version 3 of the License, or (at your option) + * any later version. + * + * Cleanflight and Betaflight are distributed in the hope that they + * will be useful, but WITHOUT ANY WARRANTY; without even the implied + * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + * See the GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this software. + * + * If not, see . + */ + +#include +#include +#include + +#include + +//#include "platform.h" +// +//#include "build/build_config.h" +//#include "build/debug.h" +// +//#include "common/maths.h" +//#include "common/utils.h" +//#include "common/filter.h" +// +//#include "config/config_reset.h" +//#include "config/feature.h" +// +//#include "drivers/adc.h" +//#include "drivers/rx/rx_pwm.h" +//#include "drivers/rx/rx_spi.h" +//#include "drivers/time.h" +// +//#include "fc/config.h" +//#include "fc/rc_controls.h" +//#include "fc/rc_modes.h" +// +//#include "flight/failsafe.h" +// +//#include "io/serial.h" +// +//#include "pg/pg.h" +//#include "pg/pg_ids.h" +//#include "pg/rx.h" +// +//#include "rx/rx.h" +//#include "rx/pwm.h" +//#include "rx/fport.h" +//#include "rx/sbus.h" +//#include "rx/spektrum.h" +//#include "rx/srxl2.h" +//#include "rx/sumd.h" +//#include "rx/sumh.h" +//#include "rx/msp.h" +//#include "rx/xbus.h" +//#include "rx/ibus.h" +//#include "rx/jetiexbus.h" +//#include "rx/crsf.h" +//#include "rx/rx_spi.h" +//#include "rx/targetcustomserial.h" +// +// +//const char rcChannelLetters[] = "AERT12345678abcdefgh"; + +static uint16_t rssi = 0; // range: [0;1023] +//static uint8_t rssi_dbm = 130; // range: [0;130] display 0 to -130 +//static timeUs_t lastMspRssiUpdateUs = 0; + +static pt1Filter_t frameErrFilter; + +//#ifdef USE_RX_LINK_QUALITY_INFO +//static uint16_t linkQuality = 0; +//#endif +// +//#define MSP_RSSI_TIMEOUT_US 1500000 // 1.5 sec +// +//#define RSSI_ADC_DIVISOR (4096 / 1024) +//#define RSSI_OFFSET_SCALING (1024 / 100.0f) + +rssiSource_e rssiSource; +//linkQualitySource_e linkQualitySource; +// +//static bool rxDataProcessingRequired = false; +//static bool auxiliaryProcessingRequired = false; +// +//static bool rxSignalReceived = false; +//static bool rxFlightChannelsValid = false; +//static bool rxIsInFailsafeMode = true; +static uint8_t rxChannelCount; + +//static timeUs_t rxNextUpdateAtUs = 0; +//static uint32_t needRxSignalBefore = 0; +static uint32_t needRxSignalMaxDelayUs; +//static uint32_t suspendRxSignalUntil = 0; +//static uint8_t skipRxSamples = 0; +// +//static int16_t rcRaw[MAX_SUPPORTED_RC_CHANNEL_COUNT]; // interval [1000;2000] +int16_t rcData[MAX_SUPPORTED_RC_CHANNEL_COUNT]; // interval [1000;2000] +uint32_t rcInvalidPulsPeriod[MAX_SUPPORTED_RC_CHANNEL_COUNT]; + +#define MAX_INVALID_PULS_TIME 300 +//#define PPM_AND_PWM_SAMPLE_COUNT 3 +// +//#define DELAY_50_HZ (1000000 / 50) +//#define DELAY_33_HZ (1000000 / 33) +#define DELAY_10_HZ (1000000 / 10) +//#define DELAY_5_HZ (1000000 / 5) +//#define SKIP_RC_ON_SUSPEND_PERIOD 1500000 // 1.5 second period in usec (call frequency independent) +//#define SKIP_RC_SAMPLES_ON_RESUME 2 // flush 2 samples to drop wrong measurements (timing independent) + +rxRuntimeConfig_t rxRuntimeConfig; +static uint8_t rcSampleIndex = 0; + +//PG_REGISTER_ARRAY_WITH_RESET_FN(rxChannelRangeConfig_t, NON_AUX_CHANNEL_COUNT, rxChannelRangeConfigs, PG_RX_CHANNEL_RANGE_CONFIG, 0); +//void pgResetFn_rxChannelRangeConfigs(rxChannelRangeConfig_t *rxChannelRangeConfigs) +//{ +// // set default calibration to full range and 1:1 mapping +// for (int i = 0; i < NON_AUX_CHANNEL_COUNT; i++) { +// rxChannelRangeConfigs[i].min = PWM_RANGE_MIN; +// rxChannelRangeConfigs[i].max = PWM_RANGE_MAX; +// } +//} +// +//PG_REGISTER_ARRAY_WITH_RESET_FN(rxFailsafeChannelConfig_t, MAX_SUPPORTED_RC_CHANNEL_COUNT, rxFailsafeChannelConfigs, PG_RX_FAILSAFE_CHANNEL_CONFIG, 0); +//void pgResetFn_rxFailsafeChannelConfigs(rxFailsafeChannelConfig_t *rxFailsafeChannelConfigs) +//{ +// for (int i = 0; i < MAX_SUPPORTED_RC_CHANNEL_COUNT; i++) { +// rxFailsafeChannelConfigs[i].mode = (i < NON_AUX_CHANNEL_COUNT) ? RX_FAILSAFE_MODE_AUTO : RX_FAILSAFE_MODE_HOLD; +// rxFailsafeChannelConfigs[i].step = (i == THROTTLE) +// ? CHANNEL_VALUE_TO_RXFAIL_STEP(RX_MIN_USEC) +// : CHANNEL_VALUE_TO_RXFAIL_STEP(RX_MID_USEC); +// } +//} +// +//void resetAllRxChannelRangeConfigurations(rxChannelRangeConfig_t *rxChannelRangeConfig) { +// // set default calibration to full range and 1:1 mapping +// for (int i = 0; i < NON_AUX_CHANNEL_COUNT; i++) { +// rxChannelRangeConfig->min = PWM_RANGE_MIN; +// rxChannelRangeConfig->max = PWM_RANGE_MAX; +// rxChannelRangeConfig++; +// } +//} + +static uint16_t nullReadRawRC(const rxRuntimeConfig_t *rxRuntimeConfig, uint8_t channel) +{ + UNUSED(rxRuntimeConfig); + UNUSED(channel); + + return PPM_RCVR_TIMEOUT; +} + +static uint8_t nullFrameStatus(rxRuntimeConfig_t *rxRuntimeConfig) +{ + UNUSED(rxRuntimeConfig); + + return RX_FRAME_PENDING; +} + +static bool nullProcessFrame(const rxRuntimeConfig_t *rxRuntimeConfig) +{ + UNUSED(rxRuntimeConfig); + + return true; +} + +//STATIC_UNIT_TESTED bool isPulseValid(uint16_t pulseDuration) +//{ +// return pulseDuration >= rxConfig()->rx_min_usec && +// pulseDuration <= rxConfig()->rx_max_usec; +//} +// +//#ifdef USE_SERIAL_RX +//static bool serialRxInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig) +//{ +// bool enabled = false; +// switch (rxRuntimeConfig->serialrxProvider) { +//#ifdef USE_SERIALRX_SRXL2 +// case SERIALRX_SRXL2: +// enabled = srxl2RxInit(rxConfig, rxRuntimeConfig); +// break; +//#endif +//#ifdef USE_SERIALRX_SPEKTRUM +// case SERIALRX_SRXL: +// case SERIALRX_SPEKTRUM1024: +// case SERIALRX_SPEKTRUM2048: +// enabled = spektrumInit(rxConfig, rxRuntimeConfig); +// break; +//#endif +//#ifdef USE_SERIALRX_SBUS +// case SERIALRX_SBUS: +// enabled = sbusInit(rxConfig, rxRuntimeConfig); +// break; +//#endif +//#ifdef USE_SERIALRX_SUMD +// case SERIALRX_SUMD: +// enabled = sumdInit(rxConfig, rxRuntimeConfig); +// break; +//#endif +//#ifdef USE_SERIALRX_SUMH +// case SERIALRX_SUMH: +// enabled = sumhInit(rxConfig, rxRuntimeConfig); +// break; +//#endif +//#ifdef USE_SERIALRX_XBUS +// case SERIALRX_XBUS_MODE_B: +// case SERIALRX_XBUS_MODE_B_RJ01: +// enabled = xBusInit(rxConfig, rxRuntimeConfig); +// break; +//#endif +//#ifdef USE_SERIALRX_IBUS +// case SERIALRX_IBUS: +// enabled = ibusInit(rxConfig, rxRuntimeConfig); +// break; +//#endif +//#ifdef USE_SERIALRX_JETIEXBUS +// case SERIALRX_JETIEXBUS: +// enabled = jetiExBusInit(rxConfig, rxRuntimeConfig); +// break; +//#endif +//#ifdef USE_SERIALRX_CRSF +// case SERIALRX_CRSF: +// enabled = crsfRxInit(rxConfig, rxRuntimeConfig); +// break; +//#endif +//#ifdef USE_SERIALRX_TARGET_CUSTOM +// case SERIALRX_TARGET_CUSTOM: +// enabled = targetCustomSerialRxInit(rxConfig, rxRuntimeConfig); +// break; +//#endif +//#ifdef USE_SERIALRX_FPORT +// case SERIALRX_FPORT: +// enabled = fportRxInit(rxConfig, rxRuntimeConfig); +// break; +//#endif +// default: +// enabled = false; +// break; +// } +// return enabled; +//} +//#endif + +void rxInit(void) +{ + if (featureIsEnabled(FEATURE_RX_PARALLEL_PWM)) { + rxRuntimeConfig.rxProvider = RX_PROVIDER_PARALLEL_PWM; + } else if (featureIsEnabled(FEATURE_RX_PPM)) { + rxRuntimeConfig.rxProvider = RX_PROVIDER_PPM; + } else if (featureIsEnabled(FEATURE_RX_SERIAL)) { + rxRuntimeConfig.rxProvider = RX_PROVIDER_SERIAL; + } else if (featureIsEnabled(FEATURE_RX_MSP)) { + rxRuntimeConfig.rxProvider = RX_PROVIDER_MSP; + } else if (featureIsEnabled(FEATURE_RX_SPI)) { + rxRuntimeConfig.rxProvider = RX_PROVIDER_SPI; + } else { + rxRuntimeConfig.rxProvider = RX_PROVIDER_NONE; + } + rxRuntimeConfig.serialrxProvider = rxConfig()->serialrx_provider; + rxRuntimeConfig.rcReadRawFn = nullReadRawRC; + rxRuntimeConfig.rcFrameStatusFn = nullFrameStatus; + rxRuntimeConfig.rcProcessFrameFn = nullProcessFrame; + rcSampleIndex = 0; + needRxSignalMaxDelayUs = DELAY_10_HZ; + + for (int i = 0; i < MAX_SUPPORTED_RC_CHANNEL_COUNT; i++) { + rcData[i] = rxConfig()->midrc; + rcInvalidPulsPeriod[i] = millis() + MAX_INVALID_PULS_TIME; + } + +// rcData[THROTTLE] = (featureIsEnabled(FEATURE_3D)) ? rxConfig()->midrc : rxConfig()->rx_min_usec; +// +// // Initialize ARM switch to OFF position when arming via switch is defined +// // TODO - move to rc_mode.c +// for (int i = 0; i < MAX_MODE_ACTIVATION_CONDITION_COUNT; i++) { +// const modeActivationCondition_t *modeActivationCondition = modeActivationConditions(i); +// if (modeActivationCondition->modeId == BOXARM && IS_RANGE_USABLE(&modeActivationCondition->range)) { +// // ARM switch is defined, determine an OFF value +// uint16_t value; +// if (modeActivationCondition->range.startStep > 0) { +// value = MODE_STEP_TO_CHANNEL_VALUE((modeActivationCondition->range.startStep - 1)); +// } else { +// value = MODE_STEP_TO_CHANNEL_VALUE((modeActivationCondition->range.endStep + 1)); +// } +// // Initialize ARM AUX channel to OFF value +// rcData[modeActivationCondition->auxChannelIndex + NON_AUX_CHANNEL_COUNT] = value; +// } +// } + + switch (rxRuntimeConfig.rxProvider) { + default: + + break; +#ifdef USE_SERIAL_RX + case RX_PROVIDER_SERIAL: + { + const bool enabled = serialRxInit(rxConfig(), &rxRuntimeConfig); + if (!enabled) { + rxRuntimeConfig.rcReadRawFn = nullReadRawRC; + rxRuntimeConfig.rcFrameStatusFn = nullFrameStatus; + } + } + + break; +#endif + +#ifdef USE_RX_MSP + case RX_PROVIDER_MSP: + rxMspInit(rxConfig(), &rxRuntimeConfig); + needRxSignalMaxDelayUs = DELAY_5_HZ; + + break; +#endif + +#ifdef USE_RX_SPI + case RX_PROVIDER_SPI: + { + const bool enabled = rxSpiInit(rxSpiConfig(), &rxRuntimeConfig); + if (!enabled) { + rxRuntimeConfig.rcReadRawFn = nullReadRawRC; + rxRuntimeConfig.rcFrameStatusFn = nullFrameStatus; + } + } + + break; +#endif + +#if defined(USE_PWM) || defined(USE_PPM) + case RX_PROVIDER_PPM: + case RX_PROVIDER_PARALLEL_PWM: + rxPwmInit(rxConfig(), &rxRuntimeConfig); + + break; +#endif + } + +#if defined(USE_ADC) + if (featureIsEnabled(FEATURE_RSSI_ADC)) { + rssiSource = RSSI_SOURCE_ADC; + } else +#endif + if (rxConfig()->rssi_channel > 0) { + rssiSource = RSSI_SOURCE_RX_CHANNEL; + } + + // Setup source frame RSSI filtering to take averaged values every FRAME_ERR_RESAMPLE_US + pt1FilterInit(&frameErrFilter, pt1FilterGain(GET_FRAME_ERR_LPF_FREQUENCY(rxConfig()->rssi_src_frame_lpf_period), FRAME_ERR_RESAMPLE_US/1000000.0)); + + rxChannelCount = MIN(rxConfig()->max_aux_channel + NON_AUX_CHANNEL_COUNT, rxRuntimeConfig.channelCount); +} + +//bool rxIsReceivingSignal(void) +//{ +// return rxSignalReceived; +//} +// +//bool rxAreFlightChannelsValid(void) +//{ +// return rxFlightChannelsValid; +//} +// +//void suspendRxPwmPpmSignal(void) +//{ +//#if defined(USE_PWM) || defined(USE_PPM) +// if (rxRuntimeConfig.rxProvider == RX_PROVIDER_PARALLEL_PWM || rxRuntimeConfig.rxProvider == RX_PROVIDER_PPM) { +// suspendRxSignalUntil = micros() + SKIP_RC_ON_SUSPEND_PERIOD; +// skipRxSamples = SKIP_RC_SAMPLES_ON_RESUME; +// failsafeOnRxSuspend(SKIP_RC_ON_SUSPEND_PERIOD); +// } +//#endif +//} +// +//void resumeRxPwmPpmSignal(void) +//{ +//#if defined(USE_PWM) || defined(USE_PPM) +// if (rxRuntimeConfig.rxProvider == RX_PROVIDER_PARALLEL_PWM || rxRuntimeConfig.rxProvider == RX_PROVIDER_PPM) { +// suspendRxSignalUntil = micros(); +// skipRxSamples = SKIP_RC_SAMPLES_ON_RESUME; +// failsafeOnRxResume(); +// } +//#endif +//} +// +//#ifdef USE_RX_LINK_QUALITY_INFO +//#define LINK_QUALITY_SAMPLE_COUNT 16 +// +//STATIC_UNIT_TESTED uint16_t updateLinkQualitySamples(uint16_t value) +//{ +// static uint16_t samples[LINK_QUALITY_SAMPLE_COUNT]; +// static uint8_t sampleIndex = 0; +// static uint16_t sum = 0; +// +// sum += value - samples[sampleIndex]; +// samples[sampleIndex] = value; +// sampleIndex = (sampleIndex + 1) % LINK_QUALITY_SAMPLE_COUNT; +// return sum / LINK_QUALITY_SAMPLE_COUNT; +//} +//#endif +// +//static void setLinkQuality(bool validFrame, timeDelta_t currentDeltaTime) +//{ +//#ifdef USE_RX_LINK_QUALITY_INFO +// if (linkQualitySource != LQ_SOURCE_RX_PROTOCOL_CRSF) { +// // calculate new sample mean +// linkQuality = updateLinkQualitySamples(validFrame ? LINK_QUALITY_MAX_VALUE : 0); +// } +//#endif +// +// if (rssiSource == RSSI_SOURCE_FRAME_ERRORS) { +// static uint16_t tot_rssi = 0; +// static uint16_t cnt_rssi = 0; +// static timeDelta_t resample_time = 0; +// +// resample_time += currentDeltaTime; +// tot_rssi += validFrame ? RSSI_MAX_VALUE : 0; +// cnt_rssi++; +// +// if (resample_time >= FRAME_ERR_RESAMPLE_US) { +// setRssi(tot_rssi / cnt_rssi, rssiSource); +// tot_rssi = 0; +// cnt_rssi = 0; +// resample_time -= FRAME_ERR_RESAMPLE_US; +// } +// } +//} +// +//void setLinkQualityDirect(uint16_t linkqualityValue) +//{ +//#ifdef USE_RX_LINK_QUALITY_INFO +// linkQuality = linkqualityValue; +//#else +// UNUSED(linkqualityValue); +//#endif +//} +// +//bool rxUpdateCheck(timeUs_t currentTimeUs, timeDelta_t currentDeltaTime) +//{ +// bool signalReceived = false; +// bool useDataDrivenProcessing = true; +// +// switch (rxRuntimeConfig.rxProvider) { +// default: +// +// break; +//#if defined(USE_PWM) || defined(USE_PPM) +// case RX_PROVIDER_PPM: +// if (isPPMDataBeingReceived()) { +// signalReceived = true; +// rxIsInFailsafeMode = false; +// needRxSignalBefore = currentTimeUs + needRxSignalMaxDelayUs; +// resetPPMDataReceivedState(); +// } +// +// break; +// case RX_PROVIDER_PARALLEL_PWM: +// if (isPWMDataBeingReceived()) { +// signalReceived = true; +// rxIsInFailsafeMode = false; +// needRxSignalBefore = currentTimeUs + needRxSignalMaxDelayUs; +// useDataDrivenProcessing = false; +// } +// +// break; +//#endif +// case RX_PROVIDER_SERIAL: +// case RX_PROVIDER_MSP: +// case RX_PROVIDER_SPI: +// { +// const uint8_t frameStatus = rxRuntimeConfig.rcFrameStatusFn(&rxRuntimeConfig); +// if (frameStatus & RX_FRAME_COMPLETE) { +// rxIsInFailsafeMode = (frameStatus & RX_FRAME_FAILSAFE) != 0; +// bool rxFrameDropped = (frameStatus & RX_FRAME_DROPPED) != 0; +// signalReceived = !(rxIsInFailsafeMode || rxFrameDropped); +// if (signalReceived) { +// needRxSignalBefore = currentTimeUs + needRxSignalMaxDelayUs; +// } +// +// setLinkQuality(signalReceived, currentDeltaTime); +// } +// +// if (frameStatus & RX_FRAME_PROCESSING_REQUIRED) { +// auxiliaryProcessingRequired = true; +// } +// } +// +// break; +// } +// +// if (signalReceived) { +// rxSignalReceived = true; +// } else if (currentTimeUs >= needRxSignalBefore) { +// rxSignalReceived = false; +// } +// +// if ((signalReceived && useDataDrivenProcessing) || cmpTimeUs(currentTimeUs, rxNextUpdateAtUs) > 0) { +// rxDataProcessingRequired = true; +// } +// +// return rxDataProcessingRequired || auxiliaryProcessingRequired; // data driven or 50Hz +//} +// +//#if defined(USE_PWM) || defined(USE_PPM) +//static uint16_t calculateChannelMovingAverage(uint8_t chan, uint16_t sample) +//{ +// static int16_t rcSamples[MAX_SUPPORTED_RX_PARALLEL_PWM_OR_PPM_CHANNEL_COUNT][PPM_AND_PWM_SAMPLE_COUNT]; +// static int16_t rcDataMean[MAX_SUPPORTED_RX_PARALLEL_PWM_OR_PPM_CHANNEL_COUNT]; +// static bool rxSamplesCollected = false; +// +// const uint8_t currentSampleIndex = rcSampleIndex % PPM_AND_PWM_SAMPLE_COUNT; +// +// // update the recent samples and compute the average of them +// rcSamples[chan][currentSampleIndex] = sample; +// +// // avoid returning an incorrect average which would otherwise occur before enough samples +// if (!rxSamplesCollected) { +// if (rcSampleIndex < PPM_AND_PWM_SAMPLE_COUNT) { +// return sample; +// } +// rxSamplesCollected = true; +// } +// +// rcDataMean[chan] = 0; +// for (int sampleIndex = 0; sampleIndex < PPM_AND_PWM_SAMPLE_COUNT; sampleIndex++) { +// rcDataMean[chan] += rcSamples[chan][sampleIndex]; +// } +// return rcDataMean[chan] / PPM_AND_PWM_SAMPLE_COUNT; +//} +//#endif +// +//static uint16_t getRxfailValue(uint8_t channel) +//{ +// const rxFailsafeChannelConfig_t *channelFailsafeConfig = rxFailsafeChannelConfigs(channel); +// +// switch (channelFailsafeConfig->mode) { +// case RX_FAILSAFE_MODE_AUTO: +// switch (channel) { +// case ROLL: +// case PITCH: +// case YAW: +// return rxConfig()->midrc; +// case THROTTLE: +// if (featureIsEnabled(FEATURE_3D) && !IS_RC_MODE_ACTIVE(BOX3D) && !flight3DConfig()->switched_mode3d) { +// return rxConfig()->midrc; +// } else { +// return rxConfig()->rx_min_usec; +// } +// } +// +// FALLTHROUGH; +// default: +// case RX_FAILSAFE_MODE_INVALID: +// case RX_FAILSAFE_MODE_HOLD: +// return rcData[channel]; +// +// case RX_FAILSAFE_MODE_SET: +// return RXFAIL_STEP_TO_CHANNEL_VALUE(channelFailsafeConfig->step); +// } +//} +// +//STATIC_UNIT_TESTED uint16_t applyRxChannelRangeConfiguraton(int sample, const rxChannelRangeConfig_t *range) +//{ +// // Avoid corruption of channel with a value of PPM_RCVR_TIMEOUT +// if (sample == PPM_RCVR_TIMEOUT) { +// return PPM_RCVR_TIMEOUT; +// } +// +// sample = scaleRange(sample, range->min, range->max, PWM_RANGE_MIN, PWM_RANGE_MAX); +// sample = constrain(sample, PWM_PULSE_MIN, PWM_PULSE_MAX); +// +// return sample; +//} +// +//static void readRxChannelsApplyRanges(void) +//{ +// for (int channel = 0; channel < rxChannelCount; channel++) { +// +// const uint8_t rawChannel = channel < RX_MAPPABLE_CHANNEL_COUNT ? rxConfig()->rcmap[channel] : channel; +// +// // sample the channel +// uint16_t sample = rxRuntimeConfig.rcReadRawFn(&rxRuntimeConfig, rawChannel); +// +// // apply the rx calibration +// if (channel < NON_AUX_CHANNEL_COUNT) { +// sample = applyRxChannelRangeConfiguraton(sample, rxChannelRangeConfigs(channel)); +// } +// +// rcRaw[channel] = sample; +// } +//} +// +//static void detectAndApplySignalLossBehaviour(void) +//{ +// const uint32_t currentTimeMs = millis(); +// +// const bool useValueFromRx = rxSignalReceived && !rxIsInFailsafeMode; +// +// DEBUG_SET(DEBUG_RX_SIGNAL_LOSS, 0, rxSignalReceived); +// DEBUG_SET(DEBUG_RX_SIGNAL_LOSS, 1, rxIsInFailsafeMode); +// +// rxFlightChannelsValid = true; +// for (int channel = 0; channel < rxChannelCount; channel++) { +// uint16_t sample = rcRaw[channel]; +// +// const bool validPulse = useValueFromRx && isPulseValid(sample); +// +// if (validPulse) { +// rcInvalidPulsPeriod[channel] = currentTimeMs + MAX_INVALID_PULS_TIME; +// } else { +// if (cmp32(currentTimeMs, rcInvalidPulsPeriod[channel]) < 0) { +// continue; // skip to next channel to hold channel value MAX_INVALID_PULS_TIME +// } else { +// sample = getRxfailValue(channel); // after that apply rxfail value +// if (channel < NON_AUX_CHANNEL_COUNT) { +// rxFlightChannelsValid = false; +// } +// } +// } +//#if defined(USE_PWM) || defined(USE_PPM) +// if (rxRuntimeConfig.rxProvider == RX_PROVIDER_PARALLEL_PWM || rxRuntimeConfig.rxProvider == RX_PROVIDER_PPM) { +// // smooth output for PWM and PPM +// rcData[channel] = calculateChannelMovingAverage(channel, sample); +// } else +//#endif +// { +// rcData[channel] = sample; +// } +// } +// +// if (rxFlightChannelsValid && !IS_RC_MODE_ACTIVE(BOXFAILSAFE)) { +// failsafeOnValidDataReceived(); +// } else { +// rxIsInFailsafeMode = true; +// failsafeOnValidDataFailed(); +// for (int channel = 0; channel < rxChannelCount; channel++) { +// rcData[channel] = getRxfailValue(channel); +// } +// } +// DEBUG_SET(DEBUG_RX_SIGNAL_LOSS, 3, rcData[THROTTLE]); +//} +// +//bool calculateRxChannelsAndUpdateFailsafe(timeUs_t currentTimeUs) +//{ +// if (auxiliaryProcessingRequired) { +// auxiliaryProcessingRequired = !rxRuntimeConfig.rcProcessFrameFn(&rxRuntimeConfig); +// } +// +// if (!rxDataProcessingRequired) { +// return false; +// } +// +// rxDataProcessingRequired = false; +// rxNextUpdateAtUs = currentTimeUs + DELAY_33_HZ; +// +// // only proceed when no more samples to skip and suspend period is over +// if (skipRxSamples || currentTimeUs <= suspendRxSignalUntil) { +// if (currentTimeUs > suspendRxSignalUntil) { +// skipRxSamples--; +// } +// +// return true; +// } +// +// readRxChannelsApplyRanges(); +// detectAndApplySignalLossBehaviour(); +// +// rcSampleIndex++; +// +// return true; +//} +// +//void parseRcChannels(const char *input, rxConfig_t *rxConfig) +//{ +// for (const char *c = input; *c; c++) { +// const char *s = strchr(rcChannelLetters, *c); +// if (s && (s < rcChannelLetters + RX_MAPPABLE_CHANNEL_COUNT)) { +// rxConfig->rcmap[s - rcChannelLetters] = c - input; +// } +// } +//} + +void setRssiDirect(uint16_t newRssi, rssiSource_e source) +{ + if (source != rssiSource) { + return; + } + + rssi = newRssi; +} + +#define RSSI_SAMPLE_COUNT 16 + +static uint16_t updateRssiSamples(uint16_t value) +{ + static uint16_t samples[RSSI_SAMPLE_COUNT]; + static uint8_t sampleIndex = 0; + static unsigned sum = 0; + + sum += value - samples[sampleIndex]; + samples[sampleIndex] = value; + sampleIndex = (sampleIndex + 1) % RSSI_SAMPLE_COUNT; + return sum / RSSI_SAMPLE_COUNT; +} + +void setRssi(uint16_t rssiValue, rssiSource_e source) +{ + if (source != rssiSource) { + return; + } + + // Filter RSSI value + if (source == RSSI_SOURCE_FRAME_ERRORS) { + rssi = pt1FilterApply(&frameErrFilter, rssiValue); + } else { + // calculate new sample mean + rssi = updateRssiSamples(rssiValue); + } +} + +//void setRssiMsp(uint8_t newMspRssi) +//{ +// if (rssiSource == RSSI_SOURCE_NONE) { +// rssiSource = RSSI_SOURCE_MSP; +// } +// +// if (rssiSource == RSSI_SOURCE_MSP) { +// rssi = ((uint16_t)newMspRssi) << 2; +// lastMspRssiUpdateUs = micros(); +// } +//} +// +//static void updateRSSIPWM(void) +//{ +// // Read value of AUX channel as rssi +// int16_t pwmRssi = rcData[rxConfig()->rssi_channel - 1]; +// +// // RSSI_Invert option +// if (rxConfig()->rssi_invert) { +// pwmRssi = ((2000 - pwmRssi) + 1000); +// } +// +// // Range of rawPwmRssi is [1000;2000]. rssi should be in [0;1023]; +// setRssiDirect(constrain(((pwmRssi - 1000) / 1000.0f) * RSSI_MAX_VALUE, 0, RSSI_MAX_VALUE), RSSI_SOURCE_RX_CHANNEL); +//} +// +//static void updateRSSIADC(timeUs_t currentTimeUs) +//{ +//#ifndef USE_ADC +// UNUSED(currentTimeUs); +//#else +// static uint32_t rssiUpdateAt = 0; +// +// if ((int32_t)(currentTimeUs - rssiUpdateAt) < 0) { +// return; +// } +// rssiUpdateAt = currentTimeUs + DELAY_50_HZ; +// +// const uint16_t adcRssiSample = adcGetChannel(ADC_RSSI); +// uint16_t rssiValue = adcRssiSample / RSSI_ADC_DIVISOR; +// +// // RSSI_Invert option +// if (rxConfig()->rssi_invert) { +// rssiValue = RSSI_MAX_VALUE - rssiValue; +// } +// +// setRssi(rssiValue, RSSI_SOURCE_ADC); +//#endif +//} +// +//void updateRSSI(timeUs_t currentTimeUs) +//{ +// switch (rssiSource) { +// case RSSI_SOURCE_RX_CHANNEL: +// updateRSSIPWM(); +// break; +// case RSSI_SOURCE_ADC: +// updateRSSIADC(currentTimeUs); +// break; +// case RSSI_SOURCE_MSP: +// if (cmpTimeUs(micros(), lastMspRssiUpdateUs) > MSP_RSSI_TIMEOUT_US) { +// rssi = 0; +// } +// break; +// default: +// break; +// } +//} +// +//uint16_t getRssi(void) +//{ +// return rxConfig()->rssi_scale / 100.0f * rssi + rxConfig()->rssi_offset * RSSI_OFFSET_SCALING; +//} +// +//uint8_t getRssiPercent(void) +//{ +// return scaleRange(getRssi(), 0, RSSI_MAX_VALUE, 0, 100); +//} +// +//uint8_t getRssiDbm(void) +//{ +// return rssi_dbm; +//} +// +//#define RSSI_SAMPLE_COUNT_DBM 16 +// +//static uint8_t updateRssiDbmSamples(uint8_t value) +//{ +// static uint16_t samplesdbm[RSSI_SAMPLE_COUNT_DBM]; +// static uint8_t sampledbmIndex = 0; +// static unsigned sumdbm = 0; +// +// sumdbm += value - samplesdbm[sampledbmIndex]; +// samplesdbm[sampledbmIndex] = value; +// sampledbmIndex = (sampledbmIndex + 1) % RSSI_SAMPLE_COUNT_DBM; +// return sumdbm / RSSI_SAMPLE_COUNT_DBM; +//} +// +//void setRssiDbm(uint8_t rssiDbmValue, rssiSource_e source) +//{ +// if (source != rssiSource) { +// return; +// } +// +// rssi_dbm = updateRssiDbmSamples(rssiDbmValue); +//} +// +//void setRssiDbmDirect(uint8_t newRssiDbm, rssiSource_e source) +//{ +// if (source != rssiSource) { +// return; +// } +// +// rssi_dbm = newRssiDbm; +//} +// +//#ifdef USE_RX_LINK_QUALITY_INFO +//uint16_t rxGetLinkQuality(void) +//{ +// return linkQuality; +//} +// +//uint16_t rxGetLinkQualityPercent(void) +//{ +// return (linkQualitySource == LQ_SOURCE_RX_PROTOCOL_CRSF) ? (linkQuality / 3.41) : scaleRange(linkQuality, 0, LINK_QUALITY_MAX_VALUE, 0, 100); +//} +//#endif +// +//uint16_t rxGetRefreshRate(void) +//{ +// return rxRuntimeConfig.rxRefreshRate; +//} +// +//bool isRssiConfigured(void) +//{ +// return rssiSource != RSSI_SOURCE_NONE; +//} diff --git a/sw/airborne/subsystems/radio_control/cc2500_frsky/cc2500_rx.h b/sw/airborne/subsystems/radio_control/cc2500_frsky/cc2500_rx.h new file mode 100644 index 0000000000..f4643b8178 --- /dev/null +++ b/sw/airborne/subsystems/radio_control/cc2500_frsky/cc2500_rx.h @@ -0,0 +1,211 @@ +#include "cc2500_compat.h" + +// CAUTION: LARGE PARTS OF THIS FILE ARE COMMENTED OUT! +// betaflight/src/main/rx/rx.h @ 4e8249e +/* + * This file is part of Cleanflight and Betaflight. + * + * Cleanflight and Betaflight are free software. You can redistribute + * this software and/or modify this software under the terms of the + * GNU General Public License as published by the Free Software + * Foundation, either version 3 of the License, or (at your option) + * any later version. + * + * Cleanflight and Betaflight are distributed in the hope that they + * will be useful, but WITHOUT ANY WARRANTY; without even the implied + * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + * See the GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this software. + * + * If not, see . + */ + +#pragma once + +//#include "common/time.h" +// +//#include "pg/pg.h" +//#include "pg/rx.h" +// +//#include "drivers/io_types.h" +// +//#define STICK_CHANNEL_COUNT 4 +// +//#define PWM_RANGE_MIN 1000 +//#define PWM_RANGE_MAX 2000 +//#define PWM_RANGE_MIDDLE (PWM_RANGE_MIN + ((PWM_RANGE_MAX - PWM_RANGE_MIN) / 2)) +// +//#define PWM_PULSE_MIN 750 // minimum PWM pulse width which is considered valid +//#define PWM_PULSE_MAX 2250 // maximum PWM pulse width which is considered valid +// +//#define RXFAIL_STEP_TO_CHANNEL_VALUE(step) (PWM_PULSE_MIN + 25 * step) +//#define CHANNEL_VALUE_TO_RXFAIL_STEP(channelValue) ((constrain(channelValue, PWM_PULSE_MIN, PWM_PULSE_MAX) - PWM_PULSE_MIN) / 25) +//#define MAX_RXFAIL_RANGE_STEP ((PWM_PULSE_MAX - PWM_PULSE_MIN) / 25) +// +//#define DEFAULT_SERVO_MIN 1000 +//#define DEFAULT_SERVO_MIDDLE 1500 +//#define DEFAULT_SERVO_MAX 2000 + +typedef enum { + RX_FRAME_PENDING = 0, + RX_FRAME_COMPLETE = (1 << 0), + RX_FRAME_FAILSAFE = (1 << 1), + RX_FRAME_PROCESSING_REQUIRED = (1 << 2), + RX_FRAME_DROPPED = (1 << 3) +} rxFrameState_e; + +typedef enum { + SERIALRX_SPEKTRUM1024 = 0, + SERIALRX_SPEKTRUM2048 = 1, + SERIALRX_SBUS = 2, + SERIALRX_SUMD = 3, + SERIALRX_SUMH = 4, + SERIALRX_XBUS_MODE_B = 5, + SERIALRX_XBUS_MODE_B_RJ01 = 6, + SERIALRX_IBUS = 7, + SERIALRX_JETIEXBUS = 8, + SERIALRX_CRSF = 9, + SERIALRX_SRXL = 10, + SERIALRX_TARGET_CUSTOM = 11, + SERIALRX_FPORT = 12, + SERIALRX_SRXL2 = 13, +} SerialRXType; + +//#define MAX_SUPPORTED_RC_PPM_CHANNEL_COUNT 12 +//#define MAX_SUPPORTED_RC_PARALLEL_PWM_CHANNEL_COUNT 8 +#define MAX_SUPPORTED_RC_CHANNEL_COUNT 18 + +#define NON_AUX_CHANNEL_COUNT 4 +#define MAX_AUX_CHANNEL_COUNT (MAX_SUPPORTED_RC_CHANNEL_COUNT - NON_AUX_CHANNEL_COUNT) + +//#if MAX_SUPPORTED_RC_PARALLEL_PWM_CHANNEL_COUNT > MAX_SUPPORTED_RC_PPM_CHANNEL_COUNT +//#define MAX_SUPPORTED_RX_PARALLEL_PWM_OR_PPM_CHANNEL_COUNT MAX_SUPPORTED_RC_PARALLEL_PWM_CHANNEL_COUNT +//#else +//#define MAX_SUPPORTED_RX_PARALLEL_PWM_OR_PPM_CHANNEL_COUNT MAX_SUPPORTED_RC_PPM_CHANNEL_COUNT +//#endif +// +//extern const char rcChannelLetters[]; +// +//extern int16_t rcData[MAX_SUPPORTED_RC_CHANNEL_COUNT]; // interval [1000;2000] +// +//#define RSSI_SCALE_MIN 1 +//#define RSSI_SCALE_MAX 255 +// +//#define RSSI_SCALE_DEFAULT 100 +// +//typedef enum { +// RX_FAILSAFE_MODE_AUTO = 0, +// RX_FAILSAFE_MODE_HOLD, +// RX_FAILSAFE_MODE_SET, +// RX_FAILSAFE_MODE_INVALID +//} rxFailsafeChannelMode_e; +// +//#define RX_FAILSAFE_MODE_COUNT 3 +// +//typedef enum { +// RX_FAILSAFE_TYPE_FLIGHT = 0, +// RX_FAILSAFE_TYPE_AUX +//} rxFailsafeChannelType_e; +// +//#define RX_FAILSAFE_TYPE_COUNT 2 +// +//typedef struct rxFailsafeChannelConfig_s { +// uint8_t mode; // See rxFailsafeChannelMode_e +// uint8_t step; +//} rxFailsafeChannelConfig_t; +// +//PG_DECLARE_ARRAY(rxFailsafeChannelConfig_t, MAX_SUPPORTED_RC_CHANNEL_COUNT, rxFailsafeChannelConfigs); +// +//typedef struct rxChannelRangeConfig_s { +// uint16_t min; +// uint16_t max; +//} rxChannelRangeConfig_t; +// +//PG_DECLARE_ARRAY(rxChannelRangeConfig_t, NON_AUX_CHANNEL_COUNT, rxChannelRangeConfigs); + +struct rxRuntimeConfig_s; +typedef uint16_t (*rcReadRawDataFnPtr)(const struct rxRuntimeConfig_s *rxRuntimeConfig, uint8_t chan); // used by receiver driver to return channel data +typedef uint8_t (*rcFrameStatusFnPtr)(struct rxRuntimeConfig_s *rxRuntimeConfig); +typedef bool (*rcProcessFrameFnPtr)(const struct rxRuntimeConfig_s *rxRuntimeConfig); + +typedef enum { + RX_PROVIDER_NONE = 0, + RX_PROVIDER_PARALLEL_PWM, + RX_PROVIDER_PPM, + RX_PROVIDER_SERIAL, + RX_PROVIDER_MSP, + RX_PROVIDER_SPI, +} rxProvider_t; + +typedef struct rxRuntimeConfig_s { + rxProvider_t rxProvider; + SerialRXType serialrxProvider; + uint8_t channelCount; // number of RC channels as reported by current input driver + uint16_t rxRefreshRate; + rcReadRawDataFnPtr rcReadRawFn; + rcFrameStatusFnPtr rcFrameStatusFn; + rcProcessFrameFnPtr rcProcessFrameFn; + uint16_t *channelData; + void *frameData; +} rxRuntimeConfig_t; + +typedef enum { + RSSI_SOURCE_NONE = 0, + RSSI_SOURCE_ADC, + RSSI_SOURCE_RX_CHANNEL, + RSSI_SOURCE_RX_PROTOCOL, + RSSI_SOURCE_MSP, + RSSI_SOURCE_FRAME_ERRORS, + RSSI_SOURCE_RX_PROTOCOL_CRSF, +} rssiSource_e; + +extern rssiSource_e rssiSource; + +//typedef enum { +// LQ_SOURCE_NONE = 0, +// LQ_SOURCE_RX_PROTOCOL_CRSF, +//} linkQualitySource_e; +// +//extern linkQualitySource_e linkQualitySource; + +extern rxRuntimeConfig_t rxRuntimeConfig; //!!TODO remove this extern, only needed once for channelCount + +void rxInit(void); +//bool rxUpdateCheck(timeUs_t currentTimeUs, timeDelta_t currentDeltaTimeUs); +//bool rxIsReceivingSignal(void); +//bool rxAreFlightChannelsValid(void); +//bool calculateRxChannelsAndUpdateFailsafe(timeUs_t currentTimeUs); +// +//struct rxConfig_s; +// +//void parseRcChannels(const char *input, struct rxConfig_s *rxConfig); +// +//#define RSSI_MAX_VALUE 1023 + +void setRssiDirect(uint16_t newRssi, rssiSource_e source); +void setRssi(uint16_t rssiValue, rssiSource_e source); +//void setRssiMsp(uint8_t newMspRssi); +//void updateRSSI(timeUs_t currentTimeUs); +//uint16_t getRssi(void); +//uint8_t getRssiPercent(void); +//bool isRssiConfigured(void); +// +//#define LINK_QUALITY_MAX_VALUE 1023 +// +//uint16_t rxGetLinkQuality(void); +//void setLinkQualityDirect(uint16_t linkqualityValue); +//uint16_t rxGetLinkQualityPercent(void); +// +//uint8_t getRssiDbm(void); +//void setRssiDbm(uint8_t newRssiDbm, rssiSource_e source); +//void setRssiDbmDirect(uint8_t newRssiDbm, rssiSource_e source); +// +//void resetAllRxChannelRangeConfigurations(rxChannelRangeConfig_t *rxChannelRangeConfig); +// +//void suspendRxPwmPpmSignal(void); +//void resumeRxPwmPpmSignal(void); +// +//uint16_t rxGetRefreshRate(void); + diff --git a/sw/airborne/subsystems/radio_control/cc2500_frsky/cc2500_rx_spi.c b/sw/airborne/subsystems/radio_control/cc2500_frsky/cc2500_rx_spi.c new file mode 100644 index 0000000000..a674e98db6 --- /dev/null +++ b/sw/airborne/subsystems/radio_control/cc2500_frsky/cc2500_rx_spi.c @@ -0,0 +1,248 @@ +#include "cc2500_compat.h" + +#include "cc2500_settings.h" +#include "cc2500_rx_spi.h" +#include "cc2500_frsky_common.h" + +#define UNUSED(x) (void)(x) + +// betaflight/src/main/rx/rx_spi.c @ 766c90b +/* + * This file is part of Cleanflight and Betaflight. + * + * Cleanflight and Betaflight are free software. You can redistribute + * this software and/or modify this software under the terms of the + * GNU General Public License as published by the Free Software + * Foundation, either version 3 of the License, or (at your option) + * any later version. + * + * Cleanflight and Betaflight are distributed in the hope that they + * will be useful, but WITHOUT ANY WARRANTY; without even the implied + * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + * See the GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this software. + * + * If not, see . + */ + +#include +#include + +//#include "platform.h" + +#ifdef USE_RX_SPI + +//#include "build/build_config.h" +// +//#include "common/utils.h" +// +//#include "config/feature.h" +// +//#include "drivers/rx/rx_spi.h" +//#include "drivers/rx/rx_nrf24l01.h" +// +//#include "fc/config.h" +// +//#include "pg/rx_spi.h" +// +//#include "rx/rx_spi.h" +//#include "rx/cc2500_frsky_common.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" +//#include "rx/nrf24_kn.h" +//#include "rx/a7105_flysky.h" +//#include "rx/cc2500_sfhss.h" +//#include "rx/cyrf6936_spektrum.h" + + +uint16_t rxSpiRcData[MAX_SUPPORTED_RC_CHANNEL_COUNT]; +STATIC_UNIT_TESTED uint8_t rxSpiPayload[RX_SPI_MAX_PAYLOAD_SIZE]; +STATIC_UNIT_TESTED uint8_t rxSpiNewPacketAvailable; // set true when a new packet is received + +typedef bool (*protocolInitFnPtr)(const rxSpiConfig_t *rxSpiConfig, rxRuntimeConfig_t *rxRuntimeConfig); +typedef rx_spi_received_e (*protocolDataReceivedFnPtr)(uint8_t *payload); +typedef rx_spi_received_e (*protocolProcessFrameFnPtr)(uint8_t *payload); +typedef void (*protocolSetRcDataFromPayloadFnPtr)(uint16_t *rcData, const uint8_t *payload); + +static protocolInitFnPtr protocolInit; +static protocolDataReceivedFnPtr protocolDataReceived; +static protocolProcessFrameFnPtr protocolProcessFrame; +static protocolSetRcDataFromPayloadFnPtr protocolSetRcDataFromPayload; + +STATIC_UNIT_TESTED uint16_t rxSpiReadRawRC(const rxRuntimeConfig_t *rxRuntimeConfig, uint8_t channel) +{ + STATIC_ASSERT(NRF24L01_MAX_PAYLOAD_SIZE <= RX_SPI_MAX_PAYLOAD_SIZE, NRF24L01_MAX_PAYLOAD_SIZE_larger_than_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_V202 + case RX_SPI_NRF24_V202_250K: + case RX_SPI_NRF24_V202_1M: + protocolInit = v202Nrf24Init; + protocolDataReceived = v202Nrf24DataReceived; + protocolSetRcDataFromPayload = v202Nrf24SetRcDataFromPayload; + break; +#endif +#ifdef USE_RX_SYMA + case RX_SPI_NRF24_SYMA_X: + case RX_SPI_NRF24_SYMA_X5C: + protocolInit = symaNrf24Init; + protocolDataReceived = symaNrf24DataReceived; + protocolSetRcDataFromPayload = symaNrf24SetRcDataFromPayload; + break; +#endif +#ifdef USE_RX_CX10 + case RX_SPI_NRF24_CX10: + case RX_SPI_NRF24_CX10A: + protocolInit = cx10Nrf24Init; + protocolDataReceived = cx10Nrf24DataReceived; + protocolSetRcDataFromPayload = cx10Nrf24SetRcDataFromPayload; + break; +#endif +#ifdef USE_RX_H8_3D + case RX_SPI_NRF24_H8_3D: + protocolInit = h8_3dNrf24Init; + protocolDataReceived = h8_3dNrf24DataReceived; + protocolSetRcDataFromPayload = h8_3dNrf24SetRcDataFromPayload; + break; +#endif +#ifdef USE_RX_KN + case RX_SPI_NRF24_KN: + protocolInit = knNrf24Init; + protocolDataReceived = knNrf24DataReceived; + protocolSetRcDataFromPayload = knNrf24SetRcDataFromPayload; + break; +#endif +#ifdef USE_RX_INAV + case RX_SPI_NRF24_INAV: + protocolInit = inavNrf24Init; + protocolDataReceived = inavNrf24DataReceived; + protocolSetRcDataFromPayload = inavNrf24SetRcDataFromPayload; + break; +#endif +#if defined(USE_RX_FRSKY_SPI) +#if defined(USE_RX_FRSKY_SPI_D) + case RX_SPI_FRSKY_D: +#endif +#if defined(USE_RX_FRSKY_SPI_X) + case RX_SPI_FRSKY_X: + case RX_SPI_FRSKY_X_LBT: +#endif + protocolInit = frSkySpiInit; + protocolDataReceived = frSkySpiDataReceived; + protocolSetRcDataFromPayload = frSkySpiSetRcData; + protocolProcessFrame = frSkySpiProcessFrame; + + break; +#endif // USE_RX_FRSKY_SPI +#ifdef USE_RX_FLYSKY + case RX_SPI_A7105_FLYSKY: + case RX_SPI_A7105_FLYSKY_2A: + protocolInit = flySkyInit; + protocolDataReceived = flySkyDataReceived; + protocolSetRcDataFromPayload = flySkySetRcDataFromPayload; + break; +#endif +#ifdef USE_RX_SFHSS_SPI + case RX_SPI_SFHSS: + protocolInit = sfhssSpiInit; + protocolDataReceived = sfhssSpiDataReceived; + protocolSetRcDataFromPayload = sfhssSpiSetRcData; + break; +#endif +#ifdef USE_RX_SPEKTRUM + case RX_SPI_CYRF6936_DSM: + protocolInit = spektrumSpiInit; + protocolDataReceived = spektrumSpiDataReceived; + protocolSetRcDataFromPayload = spektrumSpiSetRcDataFromPayload; + 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) +{ + UNUSED(rxRuntimeConfig); + + uint8_t status = RX_FRAME_PENDING; + + rx_spi_received_e result = protocolDataReceived(rxSpiPayload); + + if (result & RX_SPI_RECEIVED_DATA) { + rxSpiNewPacketAvailable = true; + status = RX_FRAME_COMPLETE; + } + + if (result & RX_SPI_ROCESSING_REQUIRED) { + status |= RX_FRAME_PROCESSING_REQUIRED; + } + + return status; +} + +static bool rxSpiProcessFrame(const rxRuntimeConfig_t *rxRuntimeConfig) +{ + UNUSED(rxRuntimeConfig); + + if (protocolProcessFrame) { + rx_spi_received_e result = protocolProcessFrame(rxSpiPayload); + + if (result & RX_SPI_RECEIVED_DATA) { + rxSpiNewPacketAvailable = true; + } + + if (result & RX_SPI_ROCESSING_REQUIRED) { + return false; + } + } + + return true; +} + +/* + * Set and initialize the RX protocol + */ +bool rxSpiInit(const rxSpiConfig_t *rxSpiConfig, rxRuntimeConfig_t *rxRuntimeConfig) +{ + bool ret = false; + + if (!rxSpiDeviceInit(rxSpiConfig)) { + return false; + } + + if (rxSpiSetProtocol(rxSpiConfig->rx_spi_protocol)) { + ret = protocolInit(rxSpiConfig, rxRuntimeConfig); + } + rxSpiNewPacketAvailable = false; + rxRuntimeConfig->rxRefreshRate = 20000; + + rxRuntimeConfig->rcReadRawFn = rxSpiReadRawRC; + rxRuntimeConfig->rcFrameStatusFn = rxSpiFrameStatus; + rxRuntimeConfig->rcProcessFrameFn = rxSpiProcessFrame; + + return ret; +} +#endif diff --git a/sw/airborne/subsystems/radio_control/cc2500_frsky/cc2500_rx_spi.h b/sw/airborne/subsystems/radio_control/cc2500_frsky/cc2500_rx_spi.h new file mode 100644 index 0000000000..6614cfcc3d --- /dev/null +++ b/sw/airborne/subsystems/radio_control/cc2500_frsky/cc2500_rx_spi.h @@ -0,0 +1,91 @@ +#include "cc2500_compat.h" + +#include "cc2500_settings.h" +#include "cc2500_rx.h" + +// betaflight/src/main/rx/rx_spi.h @ 766c90b +/* + * This file is part of Cleanflight and Betaflight. + * + * Cleanflight and Betaflight are free software. You can redistribute + * this software and/or modify this software under the terms of the + * GNU General Public License as published by the Free Software + * Foundation, either version 3 of the License, or (at your option) + * any later version. + * + * Cleanflight and Betaflight are distributed in the hope that they + * will be useful, but WITHOUT ANY WARRANTY; without even the implied + * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + * See the GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this software. + * + * If not, see . + */ + +#pragma once + +//#include "pg/rx.h" +//#include "rx/rx.h" +//#include "pg/rx_spi.h" + +// Used in MSP. Append at end. +typedef enum { + RX_SPI_NRF24_V202_250K = 0, + RX_SPI_NRF24_V202_1M, + RX_SPI_NRF24_SYMA_X, + RX_SPI_NRF24_SYMA_X5C, + RX_SPI_NRF24_CX10, + RX_SPI_NRF24_CX10A, + RX_SPI_NRF24_H8_3D, + RX_SPI_NRF24_INAV, + RX_SPI_FRSKY_D, + RX_SPI_FRSKY_X, + RX_SPI_A7105_FLYSKY, + RX_SPI_A7105_FLYSKY_2A, + RX_SPI_NRF24_KN, + RX_SPI_SFHSS, + RX_SPI_CYRF6936_DSM, + RX_SPI_FRSKY_X_LBT, + RX_SPI_PROTOCOL_COUNT +} rx_spi_protocol_e; + +typedef enum { + RX_SPI_RECEIVED_NONE = 0, + RX_SPI_RECEIVED_BIND = (1 << 0), + RX_SPI_RECEIVED_DATA = (1 << 1), + RX_SPI_ROCESSING_REQUIRED = (1 << 2), +} 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 rxSpiConfig_t *rxSpiConfig, rxRuntimeConfig_t *rxRuntimeConfig); diff --git a/sw/airborne/subsystems/radio_control/cc2500_frsky/cc2500_rx_spi_common.c b/sw/airborne/subsystems/radio_control/cc2500_frsky/cc2500_rx_spi_common.c new file mode 100644 index 0000000000..a4c0123060 --- /dev/null +++ b/sw/airborne/subsystems/radio_control/cc2500_frsky/cc2500_rx_spi_common.c @@ -0,0 +1,148 @@ +#include "cc2500_compat.h" + +#include "cc2500_rx_spi_common.h" + +// betaflight/src/main/rx/rx_spi_common.c @ afb2bf5 +/* + * This file is part of Cleanflight and Betaflight. + * + * Cleanflight and Betaflight are free software. You can redistribute + * this software and/or modify this software under the terms of the + * GNU General Public License as published by the Free Software + * Foundation, either version 3 of the License, or (at your option) + * any later version. + * + * Cleanflight and Betaflight are distributed in the hope that they + * will be useful, but WITHOUT ANY WARRANTY; without even the implied + * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + * See the GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this software. + * + * If not, see . + */ + +#include +#include + +//#include "platform.h" + +#ifdef USE_RX_SPI + +//#include "drivers/io.h" +//#include "drivers/time.h" +//#include "rx/rx_spi_common.h" +//#include "rx/rx_spi.h" + +static IO_t ledPin; +static bool ledInversion = false; + +static IO_t bindPin; +static bool bindRequested; +static bool lastBindPinStatus; + +void rxSpiCommonIOInit(const rxSpiConfig_t *rxSpiConfig) +{ + if (rxSpiConfig->ledIoTag) { + ledPin = IOGetByTag(rxSpiConfig->ledIoTag); + IOInit(ledPin, OWNER_LED, 0); + IOConfigGPIO(ledPin, IOCFG_OUT_PP); + ledInversion = rxSpiConfig->ledInversion; + rxSpiLedOff(); + } else { + ledPin = IO_NONE; + } + + if (rxSpiConfig->bindIoTag) { + bindPin = IOGetByTag(rxSpiConfig->bindIoTag); + IOInit(bindPin, OWNER_RX_SPI_BIND, 0); + IOConfigGPIO(bindPin, IOCFG_IPU); + lastBindPinStatus = IORead(bindPin); + } else { + bindPin = IO_NONE; + } +} + +void rxSpiLedOn(void) +{ + if (ledPin) { + ledInversion ? IOLo(ledPin) : IOHi(ledPin); + } +} + +void rxSpiLedOff(void) +{ + if (ledPin) { + ledInversion ? IOHi(ledPin) : IOLo(ledPin); + } +} + +void rxSpiLedToggle(void) +{ + if (ledPin) { + IOToggle(ledPin); + } +} + +void rxSpiLedBlink(timeMs_t blinkMs) +{ + static timeMs_t ledBlinkMs = 0; + + if ((ledBlinkMs + blinkMs) > millis()) { + return; + } + ledBlinkMs = millis(); + + rxSpiLedToggle(); +} + +void rxSpiLedBlinkRxLoss(rx_spi_received_e result) +{ + static uint16_t rxLossCount = 0; + + if (ledPin) { + if (result == RX_SPI_RECEIVED_DATA) { + rxLossCount = 0; + rxSpiLedOn(); + } else { + if (rxLossCount < RX_LOSS_COUNT) { + rxLossCount++; + } else { + rxSpiLedBlink(INTERVAL_RX_LOSS_MS); + } + } + } +} + +void rxSpiLedBlinkBind(void) +{ + rxSpiLedBlink(INTERVAL_RX_BIND_MS); +} + +void rxSpiBind(void) +{ + bindRequested = true; +} + +bool rxSpiCheckBindRequested(bool reset) +{ + if (bindPin) { + bool bindPinStatus = IORead(bindPin); + if (lastBindPinStatus && !bindPinStatus) { + bindRequested = true; + } + lastBindPinStatus = bindPinStatus; + } + + if (!bindRequested) { + return false; + } else { + if (reset) { + bindRequested = false; + } + + return true; + } +} +#endif diff --git a/sw/airborne/subsystems/radio_control/cc2500_frsky/cc2500_rx_spi_common.h b/sw/airborne/subsystems/radio_control/cc2500_frsky/cc2500_rx_spi_common.h new file mode 100644 index 0000000000..67b24df152 --- /dev/null +++ b/sw/airborne/subsystems/radio_control/cc2500_frsky/cc2500_rx_spi_common.h @@ -0,0 +1,44 @@ +#include "cc2500_compat.h" + +#include "cc2500_rx_spi.h" + +// betaflight/src/main/rx/rx_spi_common.h @ c88a5a3 +/* + * This file is part of Cleanflight and Betaflight. + * + * Cleanflight and Betaflight are free software. You can redistribute + * this software and/or modify this software under the terms of the + * GNU General Public License as published by the Free Software + * Foundation, either version 3 of the License, or (at your option) + * any later version. + * + * Cleanflight and Betaflight are distributed in the hope that they + * will be useful, but WITHOUT ANY WARRANTY; without even the implied + * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + * See the GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this software. + * + * If not, see . + */ + +#pragma once + +//#include "rx/rx_spi.h" + +#define INTERVAL_RX_LOSS_MS 1000 +#define INTERVAL_RX_BIND_MS 250 +#define RX_LOSS_COUNT 1000 + +void rxSpiCommonIOInit(const rxSpiConfig_t *rxSpiConfig); + +void rxSpiLedOn(void); +void rxSpiLedOff(void); +void rxSpiLedToggle(void); +void rxSpiLedBlink(timeMs_t blinkMs); +void rxSpiLedBlinkRxLoss(rx_spi_received_e result); +void rxSpiLedBlinkBind(void); + +void rxSpiBind(void); +bool rxSpiCheckBindRequested(bool reset); diff --git a/sw/airborne/subsystems/radio_control/cc2500_frsky/cc2500_settings.c b/sw/airborne/subsystems/radio_control/cc2500_frsky/cc2500_settings.c new file mode 100644 index 0000000000..8d8636c2dd --- /dev/null +++ b/sw/airborne/subsystems/radio_control/cc2500_frsky/cc2500_settings.c @@ -0,0 +1,209 @@ +/* + * Copyright (C) 2019 Tom van Dijk + * + * This code is based on the betaflight cc2500 and FrskyX implementation. + * https://github.com/betaflight/betaflight + * + * This file is part of paparazzi. + * + * paparazzi 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 2, or (at your option) + * any later version. + * + * paparazzi 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 paparazzi; see the file COPYING. If not, write to + * the Free Software Foundation, 59 Temple Place - Suite 330, + * Boston, MA 02111-1307, USA. + */ + +#include "cc2500_settings.h" + +#include "cc2500_rx_spi.h" + +#include BOARD_CONFIG +#include "mcu_periph/gpio.h" +#include "generated/airframe.h" +#include "subsystems/settings.h" + +#include + + +#define _LED_GPIO(l) l ## _GPIO +#define LED_GPIO(l) _LED_GPIO(l) +#define _LED_GPIO_PIN(l) l ## _GPIO_PIN +#define LED_GPIO_PIN(l) _LED_GPIO_PIN(l) +#define _LED_GPIO_ON(l) l ## _GPIO_ON +#define LED_GPIO_ON(l) _LED_GPIO_ON(l) +#define _LED_GPIO_OFF(l) l ## _GPIO_OFF +#define LED_GPIO_OFF(l) _LED_GPIO_OFF(l) + +#define _BUTTON_GPIO(b) b ## _GPIO +#define BUTTON_GPIO(b) _BUTTON_GPIO(b) +#define _BUTTON_PIN(b) b ## _PIN +#define BUTTON_PIN(b) _BUTTON_PIN(b) + + +#ifndef CC2500_RX_SPI_PROTOCOL +#define CC2500_RX_SPI_PROTOCOL RX_SPI_FRSKY_X_LBT +#endif + +#ifndef CC2500_AUTOBIND +#define CC2500_AUTOBIND FALSE +#endif + +#ifndef CC2500_TELEMETRY_SENSORS +#define CC2500_TELEMETRY_SENSORS (SENSOR_VOLTAGE | SENSOR_CURRENT | SENSOR_FUEL | SENSOR_ALTITUDE | SENSOR_VARIO) +#endif + +static void cc2500_persistent_write(void); + + +// main/config/config.h: +void bf_writeEEPROM(void) { + // Settings storage handled by paparazzi's persistent settings + cc2500_persistent_write(); + settings_StoreSettings(1); +} + + +// main/pg/rx.h: +static rxConfig_t rxconfig; +const rxConfig_t* rxConfig(void) { + return &rxconfig; +} + + +// main/pg/rx_spi.h: +static struct gpio_t extiIo; +static struct gpio_t ledIo; +static struct gpio_t bindIo; +static rxSpiConfig_t spiconfig; +const rxSpiConfig_t* rxSpiConfig(void) { + return &spiconfig; +} + + +// main/pg/rx_spi_cc2500.h: +static rxCc2500SpiConfig_t cc2500spiconfig; +const rxCc2500SpiConfig_t* rxCc2500SpiConfig(void) { + return &cc2500spiconfig; +} +rxCc2500SpiConfig_t* rxCc2500SpiConfigMutable(void) { + return &cc2500spiconfig; +} + + +// main/telemetry/telemetry.h: +static telemetryConfig_t telemetryconfig; + +const telemetryConfig_t* telemetryConfig(void) { + return &telemetryconfig; +} + + +// main/telemetry/telemetry.h: +bool telemetryIsSensorEnabled(sensor_e sensor) { + return sensor & CC2500_TELEMETRY_SENSORS; +} + + +// Paparazzi code +struct cc2500_settings_persistent_s cc2500_settings_persistent; + +static void cc2500_persistent_write(void) { + cc2500_settings_persistent.bindVars = + cc2500spiconfig.bindTxId[0] | + cc2500spiconfig.bindTxId[1] << 8 | + cc2500spiconfig.bindOffset << 16 | + cc2500spiconfig.rxNum << 24; + for (int i = 0; i < 48; i += 4) { + cc2500_settings_persistent.bindHopData[i / 4] = + cc2500spiconfig.bindHopData[i] | + cc2500spiconfig.bindHopData[i + 1] << 8 | + cc2500spiconfig.bindHopData[i + 2] << 16 | + cc2500spiconfig.bindHopData[i + 3] << 24; + } + cc2500_settings_persistent.bindHopData[12] = + cc2500spiconfig.bindHopData[48] | + cc2500spiconfig.bindHopData[49] << 8 | + 0xFF << 24; +} + +static void cc2500_persistent_read(void) { + // Check that persistent data is loaded + // highest bindHopData byte is initialized 0 at boot + if (cc2500_settings_persistent.bindHopData[12] >> 24) { + cc2500spiconfig.bindTxId[0] = cc2500_settings_persistent.bindVars & 0xFF; + cc2500spiconfig.bindTxId[1] = (cc2500_settings_persistent.bindVars >> 8) & 0xFF; + cc2500spiconfig.bindOffset = (cc2500_settings_persistent.bindVars >> 16) & 0xFF; + cc2500spiconfig.rxNum = (cc2500_settings_persistent.bindVars >> 24) & 0xFF; + } + for (int i = 0; i < 48; i += 4) { + cc2500spiconfig.bindHopData[i] = cc2500_settings_persistent.bindHopData[i / 4] & 0xFF; + cc2500spiconfig.bindHopData[i + 1] = (cc2500_settings_persistent.bindHopData[i / 4] >> 8) & 0xFF; + cc2500spiconfig.bindHopData[i + 2] = (cc2500_settings_persistent.bindHopData[i / 4] >> 16) & 0xFF; + cc2500spiconfig.bindHopData[i + 3] = (cc2500_settings_persistent.bindHopData[i / 4] >> 24) & 0xFF; + } + cc2500spiconfig.bindHopData[48] = cc2500_settings_persistent.bindHopData[12] & 0xFF; + cc2500spiconfig.bindHopData[49] = (cc2500_settings_persistent.bindHopData[12] >> 8) & 0xFF; +} + + + +void cc2500_settings_init(void) { + // rxConfig + rxconfig.rssi_channel = 0; + rxconfig.midrc = 1500; + rxconfig.max_aux_channel = 0; // TODO + rxconfig.rssi_src_frame_lpf_period = 30; + + // rxSpiConfig + spiconfig.rx_spi_protocol = CC2500_RX_SPI_PROTOCOL; + extiIo.port = CC2500_GDO0_GPIO; + extiIo.pin = CC2500_GDO0_PIN; + spiconfig.extiIoTag = &extiIo; + +#ifdef CC2500_RX_LED + ledIo.port = LED_GPIO(CC2500_RX_LED); + ledIo.pin = LED_GPIO_PIN(CC2500_RX_LED); + ledIo.hi = LED_GPIO_ON(CC2500_RX_LED); + ledIo.lo = LED_GPIO_OFF(CC2500_RX_LED); + spiconfig.ledIoTag = &ledIo; +#else + (void) ledIo; + spiconfig.ledIoTag = NULL; +#endif + spiconfig.ledInversion = FALSE; // Handled by paparazzi LED_X_GPIO_ON|_OFF + +#ifdef CC2500_BIND_BUTTON + bindIo.port = BUTTON_GPIO(CC2500_BIND_BUTTON); + bindIo.pin = BUTTON_PIN(CC2500_BIND_BUTTON); + spiconfig.bindIoTag = &bindIo; +#else + (void) bindIo; + spiconfig.bindIoTag = NULL; +#endif + + // rxCc2500SpiConfig + cc2500spiconfig.autoBind = CC2500_AUTOBIND; + cc2500spiconfig.bindTxId[0] = 0; + cc2500spiconfig.bindTxId[1] = 0; + cc2500spiconfig.bindOffset = 0; + memset(cc2500spiconfig.bindHopData, 0, sizeof(cc2500spiconfig.bindHopData)); + cc2500spiconfig.rxNum = 0; + cc2500spiconfig.a1Source = FRSKY_SPI_A1_SOURCE_VBAT; + cc2500spiconfig.chipDetectEnabled = TRUE; + + settings_init(); + cc2500_persistent_read(); + + // telemetryConfig + telemetryconfig.pidValuesAsTelemetry = FALSE; + telemetryconfig.report_cell_voltage = FALSE; +} diff --git a/sw/airborne/subsystems/radio_control/cc2500_frsky/cc2500_settings.h b/sw/airborne/subsystems/radio_control/cc2500_frsky/cc2500_settings.h new file mode 100644 index 0000000000..241ef19b3a --- /dev/null +++ b/sw/airborne/subsystems/radio_control/cc2500_frsky/cc2500_settings.h @@ -0,0 +1,192 @@ +/* + * Copyright (C) 2019 Tom van Dijk + * + * This code is based on the betaflight cc2500 and FrskyX implementation. + * https://github.com/betaflight/betaflight + * + * This file is part of paparazzi. + * + * paparazzi 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 2, or (at your option) + * any later version. + * + * paparazzi 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 paparazzi; see the file COPYING. If not, write to + * the Free Software Foundation, 59 Temple Place - Suite 330, + * Boston, MA 02111-1307, USA. + */ + +#ifndef RADIO_CONTROL_CC2500_SETTINGS_H +#define RADIO_CONTROL_CC2500_SETTINGS_H + +#include "cc2500_compat.h" + +#include + +/* Paparazzi settings */ +void cc2500_settings_init(void); + +struct cc2500_settings_persistent_s { + uint32_t bindVars; + uint32_t bindHopData[13]; +}; +extern struct cc2500_settings_persistent_s cc2500_settings_persistent; + + +/* betaflight settings API */ +// main/config/config.h: +void bf_writeEEPROM(void); +#define writeEEPROM() bf_writeEEPROM() + + +// main/pg/rx.h: +#define FRAME_ERR_RESAMPLE_US 100000 + +#define GET_FRAME_ERR_LPF_FREQUENCY(period) (1 / (period / 10.0f)) + +typedef struct rxConfig_s { +// uint8_t rcmap[RX_MAPPABLE_CHANNEL_COUNT]; // 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_inverted; // invert the serial RX protocol compared to it's default setting +// uint8_t halfDuplex; // allow rx to operate in half duplex mode on F4, ignored for F1 and F3. +// 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_autoreset; // whenever we will reset (exit) binding mode after hard reboot + uint8_t rssi_channel; +// uint8_t rssi_scale; +// uint8_t rssi_invert; + 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 maxcheck; // maximum rc end +// uint8_t rcInterpolation; +// uint8_t rcInterpolationChannels; +// uint8_t rcInterpolationInterval; +// uint8_t fpvCamAngleDegrees; // Camera angle to be scaled into rc commands +// uint8_t airModeActivateThreshold; // Throttle setpoint percent where airmode gets activated +// +// uint16_t rx_min_usec; +// uint16_t rx_max_usec; + uint8_t max_aux_channel; +// uint8_t rssi_src_frame_errors; // true to use frame drop flags in the rx protocol +// int8_t rssi_offset; // offset applied to the RSSI value before it is returned +// uint8_t rc_smoothing_type; // Determines the smoothing algorithm to use: INTERPOLATION or FILTER +// uint8_t rc_smoothing_input_cutoff; // Filter cutoff frequency for the input filter (0 = auto) +// uint8_t rc_smoothing_derivative_cutoff; // Filter cutoff frequency for the setpoint weight derivative filter (0 = auto) +// uint8_t rc_smoothing_debug_axis; // Axis to log as debug values when debug_mode = RC_SMOOTHING +// uint8_t rc_smoothing_input_type; // Input filter type (0 = PT1, 1 = BIQUAD) +// uint8_t rc_smoothing_derivative_type; // Derivative filter type (0 = OFF, 1 = PT1, 2 = BIQUAD) +// uint8_t rc_smoothing_auto_factor; // Used to adjust the "smoothness" determined by the auto cutoff calculations + uint8_t rssi_src_frame_lpf_period; // Period of the cutoff frequency for the source frame RSSI filter (in 0.1 s) +// +// uint8_t srxl2_unit_id; // Spektrum SRXL2 RX unit id +// uint8_t srxl2_baud_fast; // Select Spektrum SRXL2 fast baud rate +// uint8_t sbus_baud_fast; // Select SBus fast baud rate +} rxConfig_t; + +const rxConfig_t* rxConfig(void); + +// main/pg/rx_spi.h: +typedef struct rxSpiConfig_s { + // RX protocol + uint8_t rx_spi_protocol; // type of SPI RX protocol +// // nrf24: 0 = v202 250kbps. (Must be enabled by FEATURE_RX_NRF24 first.) +// uint32_t rx_spi_id; +// uint8_t rx_spi_rf_channel_count; +// +// // SPI Bus +// ioTag_t csnTag; +// uint8_t spibus; +// + ioTag_t bindIoTag; + ioTag_t ledIoTag; + uint8_t ledInversion; + + ioTag_t extiIoTag; +} rxSpiConfig_t; + +const rxSpiConfig_t* rxSpiConfig(void); + + +// main/pg/rx_spi_cc2500.h: +typedef enum { + FRSKY_SPI_A1_SOURCE_VBAT = 0, + FRSKY_SPI_A1_SOURCE_EXTADC, + FRSKY_SPI_A1_SOURCE_CONST +} frSkySpiA1Source_e; + +typedef struct rxCc2500SpiConfig_s { + uint8_t autoBind; + uint8_t bindTxId[2]; + int8_t bindOffset; + uint8_t bindHopData[50]; + uint8_t rxNum; + uint8_t a1Source; + uint8_t chipDetectEnabled; +// ioTag_t txEnIoTag; +// ioTag_t lnaEnIoTag; +// ioTag_t antSelIoTag; +} rxCc2500SpiConfig_t; + +const rxCc2500SpiConfig_t* rxCc2500SpiConfig(void); +rxCc2500SpiConfig_t* rxCc2500SpiConfigMutable(void); + + +// main/telemetry/telemetry.h: +typedef struct telemetryConfig_s { +// int16_t gpsNoFixLatitude; +// int16_t gpsNoFixLongitude; +// uint8_t telemetry_inverted; +// uint8_t halfDuplex; +// frskyGpsCoordFormat_e frsky_coordinate_format; +// frskyUnit_e frsky_unit; +// uint8_t frsky_vfas_precision; +// uint8_t hottAlarmSoundInterval; + uint8_t pidValuesAsTelemetry; + uint8_t report_cell_voltage; +// uint8_t flysky_sensors[IBUS_SENSOR_COUNT]; +// uint16_t mavlink_mah_as_heading_divisor; +// uint32_t disabledSensors; // bit flags +} telemetryConfig_t; + +const telemetryConfig_t* telemetryConfig(void); + +typedef enum { + SENSOR_VOLTAGE = 1 << 0, + SENSOR_CURRENT = 1 << 1, + SENSOR_FUEL = 1 << 2, + SENSOR_MODE = 1 << 3, + SENSOR_ACC_X = 1 << 4, + SENSOR_ACC_Y = 1 << 5, + SENSOR_ACC_Z = 1 << 6, + SENSOR_PITCH = 1 << 7, + SENSOR_ROLL = 1 << 8, + SENSOR_HEADING = 1 << 9, + SENSOR_ALTITUDE = 1 << 10, + SENSOR_VARIO = 1 << 11, + SENSOR_LAT_LONG = 1 << 12, + SENSOR_GROUND_SPEED = 1 << 13, + SENSOR_DISTANCE = 1 << 14, + ESC_SENSOR_CURRENT = 1 << 15, + ESC_SENSOR_VOLTAGE = 1 << 16, + ESC_SENSOR_RPM = 1 << 17, + ESC_SENSOR_TEMPERATURE = 1 << 18, + ESC_SENSOR_ALL = ESC_SENSOR_CURRENT \ + | ESC_SENSOR_VOLTAGE \ + | ESC_SENSOR_RPM \ + | ESC_SENSOR_TEMPERATURE, + SENSOR_TEMPERATURE = 1 << 19, + SENSOR_ALL = (1 << 20) - 1, +} sensor_e; +#define SENSOR_NONE 0 + +bool telemetryIsSensorEnabled(sensor_e sensor); + + +#endif // RADIO_CONTROL_CC2500_SETTINGS_H diff --git a/sw/airborne/subsystems/radio_control/cc2500_frsky/cc2500_smartport.c b/sw/airborne/subsystems/radio_control/cc2500_frsky/cc2500_smartport.c new file mode 100644 index 0000000000..f5e3052161 --- /dev/null +++ b/sw/airborne/subsystems/radio_control/cc2500_frsky/cc2500_smartport.c @@ -0,0 +1,931 @@ +#include "cc2500_compat.h" + +#include "cc2500_rx.h" +#include "cc2500_settings.h" +#include "cc2500_smartport.h" + +#include "subsystems/datalink/downlink.h" + +#ifdef UNUSED +#undef UNUSED +#define UNUSED(x) (void)(x) +#endif + +#ifdef USE_GPS +#undef USE_GPS +#endif + +//#define FSSP_DATAID_DOWNLINK 0x0B71 // DEBUG +#define FSSP_DATAID_DOWNLINK 0x5015 +#define FSSP_DATAID_UPLINK 0x5016 + +smartPortDownlinkFn *smartPortDownlink = NULL; +smartPortUplinkFn *smartPortUplink = NULL; + +// CAUTION: added DOWNLINK sensor to code below! +// CAUTION: added payload handling to processSmartPortTelemetry +// CAUTION: LARGE PARTS OF THIS FILE ARE COMMENTED OUT! +// betaflight/src/main/telemetry/smartport.c @ 443869e +/* + * This file is part of Cleanflight and Betaflight. + * + * Cleanflight and Betaflight are free software. You can redistribute + * this software and/or modify this software under the terms of the + * GNU General Public License as published by the Free Software + * Foundation, either version 3 of the License, or (at your option) + * any later version. + * + * Cleanflight and Betaflight are distributed in the hope that they + * will be useful, but WITHOUT ANY WARRANTY; without even the implied + * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + * See the GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this software. + * + * If not, see . + */ + +/* + * SmartPort Telemetry implementation by frank26080115 + * see https://github.com/frank26080115/cleanflight/wiki/Using-Smart-Port + */ +#include +#include +#include +#include +#include + +//#include "platform.h" +// +//#if defined(USE_TELEMETRY_SMARTPORT) +// +//#include "common/axis.h" +//#include "common/color.h" +//#include "common/maths.h" +//#include "common/utils.h" +// +//#include "config/feature.h" +// +//#include "drivers/accgyro/accgyro.h" +//#include "drivers/compass/compass.h" +//#include "drivers/sensor.h" +//#include "drivers/time.h" +// +//#include "fc/config.h" +//#include "fc/controlrate_profile.h" +//#include "fc/rc_controls.h" +//#include "fc/runtime_config.h" +// +//#include "flight/failsafe.h" +//#include "flight/imu.h" +//#include "flight/mixer.h" +//#include "flight/pid.h" +//#include "flight/position.h" +// +//#include "io/beeper.h" +//#include "io/gps.h" +//#include "io/motors.h" +//#include "io/serial.h" +// +//#include "msp/msp.h" +// +//#include "rx/rx.h" +// +//#include "pg/pg.h" +//#include "pg/pg_ids.h" +//#include "pg/rx.h" +// +//#include "sensors/acceleration.h" +//#include "sensors/adcinternal.h" +//#include "sensors/barometer.h" +//#include "sensors/battery.h" +//#include "sensors/boardalignment.h" +//#include "sensors/compass.h" +//#include "sensors/esc_sensor.h" +//#include "sensors/gyro.h" +//#include "sensors/sensors.h" +// +//#include "telemetry/msp_shared.h" +//#include "telemetry/smartport.h" +//#include "telemetry/telemetry.h" +// +//#define SMARTPORT_MIN_TELEMETRY_RESPONSE_DELAY_US 500 + +// these data identifiers are obtained from https://github.com/opentx/opentx/blob/master/radio/src/telemetry/frsky_hub.h +enum +{ + FSSP_DATAID_SPEED = 0x0830 , + FSSP_DATAID_VFAS = 0x0210 , + FSSP_DATAID_VFAS1 = 0x0211 , + FSSP_DATAID_VFAS2 = 0x0212 , + FSSP_DATAID_VFAS3 = 0x0213 , + FSSP_DATAID_VFAS4 = 0x0214 , + FSSP_DATAID_VFAS5 = 0x0215 , + FSSP_DATAID_VFAS6 = 0x0216 , + FSSP_DATAID_VFAS7 = 0x0217 , + FSSP_DATAID_VFAS8 = 0x0218 , + FSSP_DATAID_CURRENT = 0x0200 , + FSSP_DATAID_CURRENT1 = 0x0201 , + FSSP_DATAID_CURRENT2 = 0x0202 , + FSSP_DATAID_CURRENT3 = 0x0203 , + FSSP_DATAID_CURRENT4 = 0x0204 , + FSSP_DATAID_CURRENT5 = 0x0205 , + FSSP_DATAID_CURRENT6 = 0x0206 , + FSSP_DATAID_CURRENT7 = 0x0207 , + FSSP_DATAID_CURRENT8 = 0x0208 , + FSSP_DATAID_RPM = 0x0500 , + FSSP_DATAID_RPM1 = 0x0501 , + FSSP_DATAID_RPM2 = 0x0502 , + FSSP_DATAID_RPM3 = 0x0503 , + FSSP_DATAID_RPM4 = 0x0504 , + FSSP_DATAID_RPM5 = 0x0505 , + FSSP_DATAID_RPM6 = 0x0506 , + FSSP_DATAID_RPM7 = 0x0507 , + FSSP_DATAID_RPM8 = 0x0508 , + FSSP_DATAID_ALTITUDE = 0x0100 , + FSSP_DATAID_FUEL = 0x0600 , + FSSP_DATAID_ADC1 = 0xF102 , + FSSP_DATAID_ADC2 = 0xF103 , + FSSP_DATAID_LATLONG = 0x0800 , + FSSP_DATAID_CAP_USED = 0x0600 , + FSSP_DATAID_VARIO = 0x0110 , + FSSP_DATAID_CELLS = 0x0300 , + FSSP_DATAID_CELLS_LAST = 0x030F , + FSSP_DATAID_HEADING = 0x0840 , +#if defined(USE_ACC) + FSSP_DATAID_ACCX = 0x0700 , + FSSP_DATAID_ACCY = 0x0710 , + FSSP_DATAID_ACCZ = 0x0720 , +#endif + FSSP_DATAID_T1 = 0x0400 , + FSSP_DATAID_T11 = 0x0401 , + FSSP_DATAID_T2 = 0x0410 , + FSSP_DATAID_HOME_DIST = 0x0420 , + FSSP_DATAID_GPS_ALT = 0x0820 , + FSSP_DATAID_ASPD = 0x0A00 , + FSSP_DATAID_TEMP = 0x0B70 , + FSSP_DATAID_TEMP1 = 0x0B71 , + FSSP_DATAID_TEMP2 = 0x0B72 , + FSSP_DATAID_TEMP3 = 0x0B73 , + FSSP_DATAID_TEMP4 = 0x0B74 , + FSSP_DATAID_TEMP5 = 0x0B75 , + FSSP_DATAID_TEMP6 = 0x0B76 , + FSSP_DATAID_TEMP7 = 0x0B77 , + FSSP_DATAID_TEMP8 = 0x0B78 , + FSSP_DATAID_A3 = 0x0900 , + FSSP_DATAID_A4 = 0x0910 +}; + +// if adding more sensors then increase this value +#define MAX_DATAIDS 18 + +static uint16_t frSkyDataIdTable[MAX_DATAIDS]; + +//#ifdef USE_ESC_SENSOR_TELEMETRY +//// number of sensors to send between sending the ESC sensors +//#define ESC_SENSOR_PERIOD 7 +// +//// if adding more esc sensors then increase this value +//#define MAX_ESC_DATAIDS 4 +// +//static uint16_t frSkyEscDataIdTable[MAX_ESC_DATAIDS]; +//#endif + +typedef struct frSkyTableInfo_s { + uint16_t * table; + uint8_t size; + uint8_t index; +} frSkyTableInfo_t; + +static frSkyTableInfo_t frSkyDataIdTableInfo = { frSkyDataIdTable, 0, 0 }; +//#ifdef USE_ESC_SENSOR_TELEMETRY +//static frSkyTableInfo_t frSkyEscDataIdTableInfo = {frSkyEscDataIdTable, 0, 0}; +//#endif +// +//#define SMARTPORT_BAUD 57600 +//#define SMARTPORT_UART_MODE MODE_RXTX +//#define SMARTPORT_SERVICE_TIMEOUT_US 1000 // max allowed time to find a value to send +// +//static serialPort_t *smartPortSerialPort = NULL; // The 'SmartPort'(tm) Port. +//static serialPortConfig_t *portConfig; +// +//static portSharing_e smartPortPortSharing; + +enum +{ + TELEMETRY_STATE_UNINITIALIZED, + TELEMETRY_STATE_INITIALIZED_SERIAL, + TELEMETRY_STATE_INITIALIZED_EXTERNAL, +}; + +static uint8_t telemetryState = TELEMETRY_STATE_UNINITIALIZED; + +//typedef struct smartPortFrame_s { +// uint8_t sensorId; +// smartPortPayload_t payload; +// uint8_t crc; +//} __attribute__((packed)) smartPortFrame_t; +// +//#define SMARTPORT_MSP_PAYLOAD_SIZE (sizeof(smartPortPayload_t) - sizeof(uint8_t)) + +static smartPortWriteFrameFn *smartPortWriteFrame; + +//#if defined(USE_MSP_OVER_TELEMETRY) +//static bool smartPortMspReplyPending = false; +//#endif + +smartPortPayload_t *smartPortDataReceive(uint16_t c, bool *clearToSend, smartPortCheckQueueEmptyFn *checkQueueEmpty, bool useChecksum) +{ + static uint8_t rxBuffer[sizeof(smartPortPayload_t)]; + static uint8_t smartPortRxBytes = 0; + static bool skipUntilStart = true; + static bool awaitingSensorId = false; + static bool byteStuffing = false; + static uint16_t checksum = 0; + + if (c == FSSP_START_STOP) { + *clearToSend = false; + smartPortRxBytes = 0; + awaitingSensorId = true; + skipUntilStart = false; + + return NULL; + } else if (skipUntilStart) { + return NULL; + } + + if (awaitingSensorId) { + awaitingSensorId = false; + if ((c == FSSP_SENSOR_ID1) && checkQueueEmpty()) { + // our slot is starting, no need to decode more + *clearToSend = true; + skipUntilStart = true; + } else if (c == FSSP_SENSOR_ID2) { + checksum = 0; + } else { + skipUntilStart = true; + } + } else { + if (c == FSSP_DLE) { + byteStuffing = true; + + return NULL; + } else if (byteStuffing) { + c ^= FSSP_DLE_XOR; + byteStuffing = false; + } + + if (smartPortRxBytes < sizeof(smartPortPayload_t)) { + rxBuffer[smartPortRxBytes++] = (uint8_t)c; + checksum += c; + + if (!useChecksum && (smartPortRxBytes == sizeof(smartPortPayload_t))) { + skipUntilStart = true; + + return (smartPortPayload_t *)&rxBuffer; + } + } else { + skipUntilStart = true; + + checksum += c; + checksum = (checksum & 0xFF) + (checksum >> 8); + if (checksum == 0xFF) { + return (smartPortPayload_t *)&rxBuffer; + } + } + } + + return NULL; +} + +//void smartPortSendByte(uint8_t c, uint16_t *checksum, serialPort_t *port) +//{ +// // smart port escape sequence +// if (c == FSSP_DLE || c == FSSP_START_STOP) { +// serialWrite(port, FSSP_DLE); +// serialWrite(port, c ^ FSSP_DLE_XOR); +// } else { +// serialWrite(port, c); +// } +// +// if (checksum != NULL) { +// *checksum += c; +// } +//} +// +//bool smartPortPayloadContainsMSP(const smartPortPayload_t *payload) +//{ +// return payload->frameId == FSSP_MSPC_FRAME_SMARTPORT || payload->frameId == FSSP_MSPC_FRAME_FPORT; +//} +// +//void smartPortWriteFrameSerial(const smartPortPayload_t *payload, serialPort_t *port, uint16_t checksum) +//{ +// uint8_t *data = (uint8_t *)payload; +// for (unsigned i = 0; i < sizeof(smartPortPayload_t); i++) { +// smartPortSendByte(*data++, &checksum, port); +// } +// checksum = 0xff - ((checksum & 0xff) + (checksum >> 8)); +// smartPortSendByte((uint8_t)checksum, NULL, port); +//} +// +//static void smartPortWriteFrameInternal(const smartPortPayload_t *payload) +//{ +// smartPortWriteFrameSerial(payload, smartPortSerialPort, 0); +//} + +static void smartPortSendPackage(uint16_t id, uint32_t val) +{ + smartPortPayload_t payload; + payload.frameId = FSSP_DATA_FRAME; + payload.valueId = id; + payload.data = val; + + smartPortWriteFrame(&payload); +} + +#define ADD_SENSOR(dataId) frSkyDataIdTableInfo.table[frSkyDataIdTableInfo.index++] = dataId +#define ADD_ESC_SENSOR(dataId) frSkyEscDataIdTableInfo.table[frSkyEscDataIdTableInfo.index++] = dataId + +static void initSmartPortSensors(void) +{ + frSkyDataIdTableInfo.index = 0; + + if (telemetryIsSensorEnabled(SENSOR_MODE)) { + ADD_SENSOR(FSSP_DATAID_T1); + ADD_SENSOR(FSSP_DATAID_T2); + } + +#if defined(USE_ADC_INTERNAL) + if (telemetryIsSensorEnabled(SENSOR_TEMPERATURE)) { + ADD_SENSOR(FSSP_DATAID_T11); + } +#endif + + if (isBatteryVoltageConfigured() && telemetryIsSensorEnabled(SENSOR_VOLTAGE)) { +#ifdef USE_ESC_SENSOR_TELEMETRY + if (!telemetryIsSensorEnabled(ESC_SENSOR_VOLTAGE)) +#endif + { + ADD_SENSOR(FSSP_DATAID_VFAS); + } + + ADD_SENSOR(FSSP_DATAID_A4); + } + + if (isAmperageConfigured() && telemetryIsSensorEnabled(SENSOR_CURRENT)) { +#ifdef USE_ESC_SENSOR_TELEMETRY + if (!telemetryIsSensorEnabled(ESC_SENSOR_CURRENT)) +#endif + { + ADD_SENSOR(FSSP_DATAID_CURRENT); + } + + if (telemetryIsSensorEnabled(SENSOR_FUEL)) { + ADD_SENSOR(FSSP_DATAID_FUEL); + } + } + + if (telemetryIsSensorEnabled(SENSOR_HEADING)) { + ADD_SENSOR(FSSP_DATAID_HEADING); + } + +#if defined(USE_ACC) + if (sensors(SENSOR_ACC)) { + if (telemetryIsSensorEnabled(SENSOR_ACC_X)) { + ADD_SENSOR(FSSP_DATAID_ACCX); + } + if (telemetryIsSensorEnabled(SENSOR_ACC_Y)) { + ADD_SENSOR(FSSP_DATAID_ACCY); + } + if (telemetryIsSensorEnabled(SENSOR_ACC_Z)) { + ADD_SENSOR(FSSP_DATAID_ACCZ); + } + } +#endif + + if (sensors(SENSOR_BARO)) { + if (telemetryIsSensorEnabled(SENSOR_ALTITUDE)) { + ADD_SENSOR(FSSP_DATAID_ALTITUDE); + } + if (telemetryIsSensorEnabled(SENSOR_VARIO)) { + ADD_SENSOR(FSSP_DATAID_VARIO); + } + } + +#ifdef USE_GPS + if (featureIsEnabled(FEATURE_GPS)) { + if (telemetryIsSensorEnabled(SENSOR_GROUND_SPEED)) { + ADD_SENSOR(FSSP_DATAID_SPEED); + } + if (telemetryIsSensorEnabled(SENSOR_LAT_LONG)) { + ADD_SENSOR(FSSP_DATAID_LATLONG); + ADD_SENSOR(FSSP_DATAID_LATLONG); // twice (one for lat, one for long) + } + if (telemetryIsSensorEnabled(SENSOR_DISTANCE)) { + ADD_SENSOR(FSSP_DATAID_HOME_DIST); + } + if (telemetryIsSensorEnabled(SENSOR_ALTITUDE)) { + ADD_SENSOR(FSSP_DATAID_GPS_ALT); + } + } +#endif + + ADD_SENSOR(FSSP_DATAID_DOWNLINK); + + frSkyDataIdTableInfo.size = frSkyDataIdTableInfo.index; + frSkyDataIdTableInfo.index = 0; + +#ifdef USE_ESC_SENSOR_TELEMETRY + frSkyEscDataIdTableInfo.index = 0; + + if (telemetryIsSensorEnabled(ESC_SENSOR_VOLTAGE)) { + ADD_ESC_SENSOR(FSSP_DATAID_VFAS); + } + if (telemetryIsSensorEnabled(ESC_SENSOR_CURRENT)) { + ADD_ESC_SENSOR(FSSP_DATAID_CURRENT); + } + if (telemetryIsSensorEnabled(ESC_SENSOR_RPM)) { + ADD_ESC_SENSOR(FSSP_DATAID_RPM); + } + if (telemetryIsSensorEnabled(ESC_SENSOR_TEMPERATURE)) { + ADD_ESC_SENSOR(FSSP_DATAID_TEMP); + } + + frSkyEscDataIdTableInfo.size = frSkyEscDataIdTableInfo.index; + frSkyEscDataIdTableInfo.index = 0; +#endif +} + +//bool initSmartPortTelemetry(void) +//{ +// if (telemetryState == TELEMETRY_STATE_UNINITIALIZED) { +// portConfig = findSerialPortConfig(FUNCTION_TELEMETRY_SMARTPORT); +// if (portConfig) { +// smartPortPortSharing = determinePortSharing(portConfig, FUNCTION_TELEMETRY_SMARTPORT); +// +// smartPortWriteFrame = smartPortWriteFrameInternal; +// +// initSmartPortSensors(); +// +// telemetryState = TELEMETRY_STATE_INITIALIZED_SERIAL; +// } +// +// return true; +// } +// +// return false; +//} + +bool initSmartPortTelemetryExternal(smartPortWriteFrameFn *smartPortWriteFrameExternal) +{ + if (telemetryState == TELEMETRY_STATE_UNINITIALIZED) { + smartPortWriteFrame = smartPortWriteFrameExternal; + + initSmartPortSensors(); + + telemetryState = TELEMETRY_STATE_INITIALIZED_EXTERNAL; + + return true; + } + + return false; +} + +//static void freeSmartPortTelemetryPort(void) +//{ +// closeSerialPort(smartPortSerialPort); +// smartPortSerialPort = NULL; +//} +// +//static void configureSmartPortTelemetryPort(void) +//{ +// if (portConfig) { +// portOptions_e portOptions = (telemetryConfig()->halfDuplex ? SERIAL_BIDIR : SERIAL_UNIDIR) | (telemetryConfig()->telemetry_inverted ? SERIAL_NOT_INVERTED : SERIAL_INVERTED); +// +// smartPortSerialPort = openSerialPort(portConfig->identifier, FUNCTION_TELEMETRY_SMARTPORT, NULL, NULL, SMARTPORT_BAUD, SMARTPORT_UART_MODE, portOptions); +// } +//} +// +//void checkSmartPortTelemetryState(void) +//{ +// if (telemetryState == TELEMETRY_STATE_INITIALIZED_SERIAL) { +// bool enableSerialTelemetry = telemetryDetermineEnabledState(smartPortPortSharing); +// +// if (enableSerialTelemetry && !smartPortSerialPort) { +// configureSmartPortTelemetryPort(); +// } else if (!enableSerialTelemetry && smartPortSerialPort) { +// freeSmartPortTelemetryPort(); +// } +// } +//} +// +//#if defined(USE_MSP_OVER_TELEMETRY) +//static void smartPortSendMspResponse(uint8_t *data) { +// smartPortPayload_t payload; +// payload.frameId = FSSP_MSPS_FRAME; +// memcpy(&payload.valueId, data, SMARTPORT_MSP_PAYLOAD_SIZE); +// +// smartPortWriteFrame(&payload); +//} +//#endif + +void processSmartPortTelemetry(smartPortPayload_t *payload, volatile bool *clearToSend, const timeUs_t *requestTimeout) +{ + static uint8_t smartPortIdCycleCnt = 0; + static uint8_t t1Cnt = 0; + static uint8_t t2Cnt = 0; + static uint8_t skipRequests = 0; +#ifdef USE_ESC_SENSOR_TELEMETRY + static uint8_t smartPortIdOffset = 0; +#endif + +#if defined(USE_MSP_OVER_TELEMETRY) + if (skipRequests) { + skipRequests--; + } else if (payload && smartPortPayloadContainsMSP(payload)) { + // Do not check the physical ID here again + // unless we start receiving other sensors' packets + // Pass only the payload: skip frameId + uint8_t *frameStart = (uint8_t *)&payload->valueId; + smartPortMspReplyPending = handleMspFrame(frameStart, SMARTPORT_MSP_PAYLOAD_SIZE, &skipRequests); + + // Don't send MSP response after write to eeprom + // CPU just got out of suspended state after writeEEPROM() + // We don't know if the receiver is listening again + // Skip a few telemetry requests before sending response + if (skipRequests) { + *clearToSend = false; + } + } +#else + UNUSED(payload); +#endif + + if (smartPortUplink && payload && payload->valueId == FSSP_DATAID_UPLINK) { + smartPortUplink(payload); + } + + bool doRun = true; + while (doRun && *clearToSend && !skipRequests) { + // Ensure we won't get stuck in the loop if there happens to be nothing available to send in a timely manner - dump the slot if we loop in there for too long. + if (requestTimeout) { + if (cmpTimeUs(micros(), *requestTimeout) >= 0) { + *clearToSend = false; + + return; + } + } else { + doRun = false; + } + +#if defined(USE_MSP_OVER_TELEMETRY) + if (smartPortMspReplyPending) { + smartPortMspReplyPending = sendMspReply(SMARTPORT_MSP_PAYLOAD_SIZE, &smartPortSendMspResponse); + *clearToSend = false; + + return; + } +#endif + + // we can send back any data we want, our tables keep track of the order and frequency of each data type we send + frSkyTableInfo_t * tableInfo = &frSkyDataIdTableInfo; + +#ifdef USE_ESC_SENSOR_TELEMETRY + if (smartPortIdCycleCnt >= ESC_SENSOR_PERIOD) { + // send ESC sensors + tableInfo = &frSkyEscDataIdTableInfo; + if (tableInfo->index == tableInfo->size) { // end of ESC table, return to other sensors + tableInfo->index = 0; + smartPortIdCycleCnt = 0; + smartPortIdOffset++; + if (smartPortIdOffset == getMotorCount() + 1) { // each motor and ESC_SENSOR_COMBINED + smartPortIdOffset = 0; + } + } + } + if (smartPortIdCycleCnt < ESC_SENSOR_PERIOD) { + // send other sensors + tableInfo = &frSkyDataIdTableInfo; +#endif + if (tableInfo->index == tableInfo->size) { // end of table reached, loop back + tableInfo->index = 0; + } +#ifdef USE_ESC_SENSOR_TELEMETRY + } +#endif + uint16_t id = tableInfo->table[tableInfo->index]; +#ifdef USE_ESC_SENSOR_TELEMETRY + if (smartPortIdCycleCnt >= ESC_SENSOR_PERIOD) { + id += smartPortIdOffset; + } +#endif + smartPortIdCycleCnt++; + tableInfo->index++; + + int32_t tmpi; + uint32_t tmp2 = 0; + uint16_t vfasVoltage; + uint8_t cellCount; + +#ifdef USE_ESC_SENSOR_TELEMETRY + escSensorData_t *escData; +#endif + + switch (id) { + case FSSP_DATAID_VFAS : + vfasVoltage = getBatteryVoltage(); + if (telemetryConfig()->report_cell_voltage) { + cellCount = getBatteryCellCount(); + vfasVoltage = cellCount ? getBatteryVoltage() / cellCount : 0; + } + smartPortSendPackage(id, vfasVoltage); // given in 0.01V, convert to volts + *clearToSend = false; + break; +#ifdef USE_ESC_SENSOR_TELEMETRY + case FSSP_DATAID_VFAS1 : + case FSSP_DATAID_VFAS2 : + case FSSP_DATAID_VFAS3 : + case FSSP_DATAID_VFAS4 : + case FSSP_DATAID_VFAS5 : + case FSSP_DATAID_VFAS6 : + case FSSP_DATAID_VFAS7 : + case FSSP_DATAID_VFAS8 : + escData = getEscSensorData(id - FSSP_DATAID_VFAS1); + if (escData != NULL) { + smartPortSendPackage(id, escData->voltage); + *clearToSend = false; + } + break; +#endif + case FSSP_DATAID_CURRENT : + smartPortSendPackage(id, getAmperage() / 10); // given in 10mA steps, unknown requested unit + *clearToSend = false; + break; +#ifdef USE_ESC_SENSOR_TELEMETRY + case FSSP_DATAID_CURRENT1 : + case FSSP_DATAID_CURRENT2 : + case FSSP_DATAID_CURRENT3 : + case FSSP_DATAID_CURRENT4 : + case FSSP_DATAID_CURRENT5 : + case FSSP_DATAID_CURRENT6 : + case FSSP_DATAID_CURRENT7 : + case FSSP_DATAID_CURRENT8 : + escData = getEscSensorData(id - FSSP_DATAID_CURRENT1); + if (escData != NULL) { + smartPortSendPackage(id, escData->current); + *clearToSend = false; + } + break; + case FSSP_DATAID_RPM : + escData = getEscSensorData(ESC_SENSOR_COMBINED); + if (escData != NULL) { + smartPortSendPackage(id, calcEscRpm(escData->rpm)); + *clearToSend = false; + } + break; + case FSSP_DATAID_RPM1 : + case FSSP_DATAID_RPM2 : + case FSSP_DATAID_RPM3 : + case FSSP_DATAID_RPM4 : + case FSSP_DATAID_RPM5 : + case FSSP_DATAID_RPM6 : + case FSSP_DATAID_RPM7 : + case FSSP_DATAID_RPM8 : + escData = getEscSensorData(id - FSSP_DATAID_RPM1); + if (escData != NULL) { + smartPortSendPackage(id, calcEscRpm(escData->rpm)); + *clearToSend = false; + } + break; + case FSSP_DATAID_TEMP : + escData = getEscSensorData(ESC_SENSOR_COMBINED); + if (escData != NULL) { + smartPortSendPackage(id, escData->temperature); + *clearToSend = false; + } + break; + case FSSP_DATAID_TEMP1 : + case FSSP_DATAID_TEMP2 : + case FSSP_DATAID_TEMP3 : + case FSSP_DATAID_TEMP4 : + case FSSP_DATAID_TEMP5 : + case FSSP_DATAID_TEMP6 : + case FSSP_DATAID_TEMP7 : + case FSSP_DATAID_TEMP8 : + escData = getEscSensorData(id - FSSP_DATAID_TEMP1); + if (escData != NULL) { + smartPortSendPackage(id, escData->temperature); + *clearToSend = false; + } + break; +#endif + case FSSP_DATAID_ALTITUDE : + smartPortSendPackage(id, getEstimatedAltitudeCm()); // unknown given unit, requested 100 = 1 meter + *clearToSend = false; + break; + case FSSP_DATAID_FUEL : + smartPortSendPackage(id, getMAhDrawn()); // given in mAh, unknown requested unit + *clearToSend = false; + break; + case FSSP_DATAID_VARIO : + smartPortSendPackage(id, getEstimatedVario()); // unknown given unit but requested in 100 = 1m/s + *clearToSend = false; + break; + case FSSP_DATAID_HEADING : + smartPortSendPackage(id, attitude.values.yaw * 10); // given in 10*deg, requested in 10000 = 100 deg + *clearToSend = false; + break; +#if defined(USE_ACC) + case FSSP_DATAID_ACCX : + smartPortSendPackage(id, lrintf(100 * acc.accADC[X] * acc.dev.acc_1G_rec)); // Multiply by 100 to show as x.xx g on Taranis + *clearToSend = false; + break; + case FSSP_DATAID_ACCY : + smartPortSendPackage(id, lrintf(100 * acc.accADC[Y] * acc.dev.acc_1G_rec)); + *clearToSend = false; + break; + case FSSP_DATAID_ACCZ : + smartPortSendPackage(id, lrintf(100 * acc.accADC[Z] * acc.dev.acc_1G_rec)); + *clearToSend = false; + break; +#endif + case FSSP_DATAID_T1 : + // we send all the flags as decimal digits for easy reading + + // the t1Cnt simply allows the telemetry view to show at least some changes + t1Cnt++; + if (t1Cnt == 4) { + t1Cnt = 1; + } + tmpi = t1Cnt * 10000; // start off with at least one digit so the most significant 0 won't be cut off + // the Taranis seems to be able to fit 5 digits on the screen + // the Taranis seems to consider this number a signed 16 bit integer + + if (!isArmingDisabled()) { + tmpi += 1; + } else { + tmpi += 2; + } + if (ARMING_FLAG(ARMED)) { + tmpi += 4; + } + + if (FLIGHT_MODE(ANGLE_MODE)) { + tmpi += 10; + } + if (FLIGHT_MODE(HORIZON_MODE)) { + tmpi += 20; + } + if (FLIGHT_MODE(PASSTHRU_MODE)) { + tmpi += 40; + } + + if (FLIGHT_MODE(MAG_MODE)) { + tmpi += 100; + } + + if (FLIGHT_MODE(HEADFREE_MODE)) { + tmpi += 4000; + } + + smartPortSendPackage(id, (uint32_t)tmpi); + *clearToSend = false; + break; + case FSSP_DATAID_T2 : +#ifdef USE_GPS + if (sensors(SENSOR_GPS)) { + // satellite accuracy HDOP: 0 = worst [HDOP > 5.5m], 9 = best [HDOP <= 1.0m] + uint16_t hdop = constrain(scaleRange(gpsSol.hdop, 100, 550, 9, 0), 0, 9) * 100; + smartPortSendPackage(id, (STATE(GPS_FIX) ? 1000 : 0) + (STATE(GPS_FIX_HOME) ? 2000 : 0) + hdop + gpsSol.numSat); + *clearToSend = false; + } else if (featureIsEnabled(FEATURE_GPS)) { + smartPortSendPackage(id, 0); + *clearToSend = false; + } else +#endif + if (telemetryConfig()->pidValuesAsTelemetry) { + switch (t2Cnt) { + case 0: + tmp2 = currentPidProfile->pid[PID_ROLL].P; + tmp2 += (currentPidProfile->pid[PID_PITCH].P<<8); + tmp2 += (currentPidProfile->pid[PID_YAW].P<<16); + break; + case 1: + tmp2 = currentPidProfile->pid[PID_ROLL].I; + tmp2 += (currentPidProfile->pid[PID_PITCH].I<<8); + tmp2 += (currentPidProfile->pid[PID_YAW].I<<16); + break; + case 2: + tmp2 = currentPidProfile->pid[PID_ROLL].D; + tmp2 += (currentPidProfile->pid[PID_PITCH].D<<8); + tmp2 += (currentPidProfile->pid[PID_YAW].D<<16); + break; + case 3: + tmp2 = currentControlRateProfile->rates[FD_ROLL]; + tmp2 += (currentControlRateProfile->rates[FD_PITCH]<<8); + tmp2 += (currentControlRateProfile->rates[FD_YAW]<<16); + break; + } + tmp2 += t2Cnt<<24; + t2Cnt++; + if (t2Cnt == 4) { + t2Cnt = 0; + } + smartPortSendPackage(id, tmp2); + *clearToSend = false; + } + + break; +#if defined(USE_ADC_INTERNAL) + case FSSP_DATAID_T11 : + smartPortSendPackage(id, getCoreTemperatureCelsius()); + *clearToSend = false; + break; +#endif +#ifdef USE_GPS + case FSSP_DATAID_SPEED : + if (STATE(GPS_FIX)) { + //convert to knots: 1cm/s = 0.0194384449 knots + //Speed should be sent in knots/1000 (GPS speed is in cm/s) + uint32_t tmpui = gpsSol.groundSpeed * 1944 / 100; + smartPortSendPackage(id, tmpui); + *clearToSend = false; + } + break; + case FSSP_DATAID_LATLONG : + if (STATE(GPS_FIX)) { + uint32_t tmpui = 0; + // the same ID is sent twice, one for longitude, one for latitude + // the MSB of the sent uint32_t helps FrSky keep track + // the even/odd bit of our counter helps us keep track + if (tableInfo->index & 1) { + tmpui = abs(gpsSol.llh.lon); // now we have unsigned value and one bit to spare + tmpui = (tmpui + tmpui / 2) / 25 | 0x80000000; // 6/100 = 1.5/25, division by power of 2 is fast + if (gpsSol.llh.lon < 0) tmpui |= 0x40000000; + } + else { + tmpui = abs(gpsSol.llh.lat); // now we have unsigned value and one bit to spare + tmpui = (tmpui + tmpui / 2) / 25; // 6/100 = 1.5/25, division by power of 2 is fast + if (gpsSol.llh.lat < 0) tmpui |= 0x40000000; + } + smartPortSendPackage(id, tmpui); + *clearToSend = false; + } + break; + case FSSP_DATAID_HOME_DIST : + if (STATE(GPS_FIX)) { + smartPortSendPackage(id, GPS_distanceToHome); + *clearToSend = false; + } + break; + case FSSP_DATAID_GPS_ALT : + if (STATE(GPS_FIX)) { + smartPortSendPackage(id, gpsSol.llh.altCm); // given in 0.01m + *clearToSend = false; + } + break; +#endif + case FSSP_DATAID_A4 : + cellCount = getBatteryCellCount(); + vfasVoltage = cellCount ? (getBatteryVoltage() / cellCount) : 0; // given in 0.01V, convert to volts + smartPortSendPackage(id, vfasVoltage); + *clearToSend = false; + break; + case FSSP_DATAID_DOWNLINK : + if (smartPortDownlink) { + uint32_t data; + if (smartPortDownlink(&data)) { + smartPortSendPackage(id, data); + *clearToSend = false; + } + } + break; + default: + break; + // if nothing is sent, hasRequest isn't cleared, we already incremented the counter, just loop back to the start + } + } +} + +//static bool serialCheckQueueEmpty(void) +//{ +// return (serialRxBytesWaiting(smartPortSerialPort) == 0); +//} +// +//void handleSmartPortTelemetry(void) +//{ +// const timeUs_t requestTimeout = micros() + SMARTPORT_SERVICE_TIMEOUT_US; +// +// if (telemetryState == TELEMETRY_STATE_INITIALIZED_SERIAL && smartPortSerialPort) { +// smartPortPayload_t *payload = NULL; +// bool clearToSend = false; +// while (serialRxBytesWaiting(smartPortSerialPort) > 0 && !payload) { +// uint8_t c = serialRead(smartPortSerialPort); +// payload = smartPortDataReceive(c, &clearToSend, serialCheckQueueEmpty, true); +// } +// +// processSmartPortTelemetry(payload, &clearToSend, &requestTimeout); +// } +//} +//#endif diff --git a/sw/airborne/subsystems/radio_control/cc2500_frsky/cc2500_smartport.h b/sw/airborne/subsystems/radio_control/cc2500_frsky/cc2500_smartport.h new file mode 100644 index 0000000000..3a3fa5dd37 --- /dev/null +++ b/sw/airborne/subsystems/radio_control/cc2500_frsky/cc2500_smartport.h @@ -0,0 +1,97 @@ +#include "cc2500_compat.h" + +/* SmartPort downlink hook + * Called from smartport telemetry loop. + * Write telemetry stream to 'data'. + * Return 'true' if data is written. + */ +typedef bool smartPortDownlinkFn(uint32_t *data); +extern smartPortDownlinkFn *smartPortDownlink; + +/* SmartPort uplink hook + * Called from processSmartPortTelemetry + */ +struct smartPortPayload_s; +typedef void smartPortUplinkFn(struct smartPortPayload_s *payload); +extern smartPortUplinkFn *smartPortUplink; + +// CAUTION: LARGE PARTS OF THIS FILE ARE COMMENTED OUT! +// betaflight/src/main/telemetry/smartport.h @ 41492e1 +/* + * This file is part of Cleanflight and Betaflight. + * + * Cleanflight and Betaflight are free software. You can redistribute + * this software and/or modify this software under the terms of the + * GNU General Public License as published by the Free Software + * Foundation, either version 3 of the License, or (at your option) + * any later version. + * + * Cleanflight and Betaflight are distributed in the hope that they + * will be useful, but WITHOUT ANY WARRANTY; without even the implied + * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + * See the GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this software. + * + * If not, see . + */ + +/* + * smartport.h + * + * Created on: 25 October 2014 + * Author: Frank26080115 + */ + +#pragma once + +#include +#include + +//#define SMARTPORT_MSP_TX_BUF_SIZE 256 +//#define SMARTPORT_MSP_RX_BUF_SIZE 64 + +enum +{ + FSSP_START_STOP = 0x7E, + + FSSP_DLE = 0x7D, + FSSP_DLE_XOR = 0x20, + + FSSP_DATA_FRAME = 0x10, + FSSP_MSPC_FRAME_SMARTPORT = 0x30, // MSP client frame + FSSP_MSPC_FRAME_FPORT = 0x31, // MSP client frame + FSSP_MSPS_FRAME = 0x32, // MSP server frame + + // ID of sensor. Must be something that is polled by FrSky RX + FSSP_SENSOR_ID1 = 0x1B, + FSSP_SENSOR_ID2 = 0x0D, + FSSP_SENSOR_ID3 = 0x34, + FSSP_SENSOR_ID4 = 0x67 + // there are 32 ID's polled by smartport master + // remaining 3 bits are crc (according to comments in openTx code) +}; + +typedef struct smartPortPayload_s { + uint8_t frameId; + uint16_t valueId; + uint32_t data; +} __attribute__((packed)) smartPortPayload_t; + +typedef void smartPortWriteFrameFn(const smartPortPayload_t *payload); +typedef bool smartPortCheckQueueEmptyFn(void); + +//bool initSmartPortTelemetry(void); +//void checkSmartPortTelemetryState(void); +bool initSmartPortTelemetryExternal(smartPortWriteFrameFn *smartPortWriteFrameExternal); + +//void handleSmartPortTelemetry(void); +void processSmartPortTelemetry(smartPortPayload_t *payload, volatile bool *hasRequest, const uint32_t *requestTimeout); + +smartPortPayload_t *smartPortDataReceive(uint16_t c, bool *clearToSend, smartPortCheckQueueEmptyFn *checkQueueEmpty, bool withChecksum); + +//struct serialPort_s; +//void smartPortWriteFrameSerial(const smartPortPayload_t *payload, struct serialPort_s *port, uint16_t checksum); +//void smartPortSendByte(uint8_t c, uint16_t *checksum, struct serialPort_s *port); +//bool smartPortPayloadContainsMSP(const smartPortPayload_t *payload); diff --git a/sw/tools/opentx_lua/sp2ser.lua b/sw/tools/opentx_lua/sp2ser.lua new file mode 100644 index 0000000000..3dbd39b116 --- /dev/null +++ b/sw/tools/opentx_lua/sp2ser.lua @@ -0,0 +1,73 @@ +-- SmartPort to serial bridge +-- TELEMETRY SCRIPT +-- +-- Requires opentx compilation flags -DLUA=YES -DUSB_SERIAL=YES -DCLI=NO +-- +-- On TX, set hardware USB mode to serial +-- Add this script as telemetry script to your model + +local downlink_str = "" +local uplink_str = "" + +local function init_func() +end + +local function downlink_bg() + local sensorId, frameId, dataId, value = sportTelemetryPop() + while frameId do + if dataId == 0x5015 then + local value0 = math.floor(value / 16777216) % 256 + local value1 = math.floor(value / 65536) % 256 + local value2 = math.floor(value / 256) % 256 + local value3 = value % 256 + serialWrite(string.char(value0) .. string.char(value1) .. string.char(value2) .. string.char(value3)) + downlink_str = string.format("0x %X %X %X %X", value0, value1, value2, value3) + end + sensorId, frameId, dataId, value = sportTelemetryPop() + end +end + +local uplink_buf = "" +local function uplink_bg() + if string.len(uplink_buf) < 4 then + -- Grab new/more data from the serial line + local new_bytes = serialRead(4 - string.len(uplink_buf)) + uplink_buf = uplink_buf .. new_bytes + end + if string.len(uplink_buf) > 0 then + -- Data ready to transmit + local sensorId = 0x0D -- see smartport.c::smartPortDataReceive + local frameId = string.len(uplink_buf) + local dataId = 0x5016 + local value = 0 + local byte = 16777216 + for i=1,string.len(uplink_buf) do + value = value + byte * string.byte(uplink_buf, i) + byte = byte / 256 + end + -- DEBUG +-- frameId = 2 +-- value = 0xABCDEF12 + -- DEBUG + local ret = sportTelemetryPush(sensorId, frameId, dataId, value) + if ret then + -- Uplink successful, signal that new data can be read + uplink_buf = "" + uplink_str = string.format("0x%X (%s)", value, frameId) + end + end +end + +local function bg_func() + downlink_bg() + uplink_bg() +end + +local function run_func(event) + lcd.clear() + lcd.drawText(1, 1, "sp2ser is running...") + lcd.drawText(1, 11, "Downlink: '" .. downlink_str .. "'") + lcd.drawText(1, 21, "Uplink: '" .. uplink_str .. "'") +end + +return {run = run_func, background = bg_func, init = init_func}