From 8882900fca91b75ed5644c855f9d3bc4cc527fdd Mon Sep 17 00:00:00 2001 From: Martin Budden Date: Mon, 13 Jun 2016 20:25:15 +0100 Subject: [PATCH] Added nrf24 reference protocol. Added CC3D targets. --- Makefile | 71 ++------------------------------- src/main/rx/nrf24.c | 8 ++++ src/main/rx/nrf24.h | 1 + src/main/rx/nrf24_ref.c | 15 +++++-- src/main/rx/nrf24_ref.h | 26 ++++++++++++ src/main/target/CC3D/CC3D_NRF24.mk | 0 src/main/target/CC3D/CC3D_OPBL_NRF24.mk | 0 src/main/target/CC3D/target.h | 38 ++++++++++++------ 8 files changed, 76 insertions(+), 83 deletions(-) create mode 100644 src/main/rx/nrf24_ref.h create mode 100644 src/main/target/CC3D/CC3D_NRF24.mk create mode 100644 src/main/target/CC3D/CC3D_OPBL_NRF24.mk diff --git a/Makefile b/Makefile index b74fff21b..91fa6daae 100644 --- a/Makefile +++ b/Makefile @@ -62,16 +62,11 @@ FEATURES = ALT_TARGETS = $(sort $(filter-out target, $(basename $(notdir $(wildcard $(ROOT)/src/main/target/*/*.mk))))) OPBL_TARGETS = $(filter %_OPBL, $(ALT_TARGETS)) -<<<<<<< HEAD #VALID_TARGETS = $(F1_TARGETS) $(F3_TARGETS) $(F4_TARGETS) VALID_TARGETS = $(dir $(wildcard $(ROOT)/src/main/target/*/target.mk)) VALID_TARGETS := $(subst /,, $(subst ./src/main/target/,, $(VALID_TARGETS))) VALID_TARGETS := $(VALID_TARGETS) $(ALT_TARGETS) VALID_TARGETS := $(sort $(VALID_TARGETS)) -======= -# Valid targets for OP BootLoader support -OPBL_TARGETS = CC3D_OPBL CC3D_OPBL_NRF24 ->>>>>>> Tidied protocols and added H8_3D protocol. ifeq ($(filter $(TARGET),$(ALT_TARGETS)), $(TARGET)) BASE_TARGET := $(firstword $(subst /,, $(subst ./src/main/target/,, $(dir $(wildcard $(ROOT)/src/main/target/*/$(TARGET).mk))))) @@ -337,27 +332,8 @@ ifneq ($(FLASH_SIZE),) DEVICE_FLAGS := $(DEVICE_FLAGS) -DFLASH_SIZE=$(FLASH_SIZE) endif -<<<<<<< HEAD TARGET_DIR = $(ROOT)/src/main/target/$(BASE_TARGET) TARGET_DIR_SRC = $(notdir $(wildcard $(TARGET_DIR)/*.c)) -======= -ifeq ($(TARGET),$(filter $(TARGET), $(CC3D_TARGETS))) -TARGET_FLAGS := $(TARGET_FLAGS) -DCC3D -ifeq ($(TARGET),CC3D_PPM1) -TARGET_FLAGS := $(TARGET_FLAGS) -DCC3D_PPM1 -CC3D_PPM1_SRC = $(CC3D_SRC) -endif -ifeq ($(TARGET),CC3D_OPBL) -TARGET_FLAGS := $(TARGET_FLAGS) -DCC3D_OPBL -CC3D_OPBL_SRC = $(CC3D_SRC) -endif -TARGET_DIR = $(ROOT)/src/main/target/CC3D -endif - -ifneq ($(filter $(TARGET),$(OPBL_TARGETS)),) -OPBL=yes -endif ->>>>>>> Tidied protocols and added H8_3D protocol. ifeq ($(OPBL),yes) TARGET_FLAGS := -DOPBL $(TARGET_FLAGS) @@ -403,11 +379,11 @@ COMMON_SRC = \ drivers/bus_spi_soft.c \ drivers/gps_i2cnav.c \ drivers/gyro_sync.c \ + drivers/rx_nrf24l01.c \ + drivers/rx_xn297.c \ drivers/pwm_mapping.c \ drivers/pwm_output.c \ drivers/pwm_rx.c \ - drivers/rx_nrf24l01.c \ - drivers/rx_xn297.c \ drivers/serial.c \ drivers/serial_uart.c \ drivers/sound_beeper.c \ @@ -435,6 +411,7 @@ COMMON_SRC = \ rx/nrf24_syma.c \ rx/nrf24_v202.c \ rx/nrf24_h8_3d.c \ + rx/nrf24_ref.c \ rx/pwm.c \ rx/rx.c \ rx/sbus.c \ @@ -528,7 +505,6 @@ STM32F4xx_COMMON_SRC = \ startup_stm32f40xx.s \ target/system_stm32f4xx.c \ drivers/accgyro_mpu.c \ -<<<<<<< HEAD drivers/adc_stm32f4xx.c \ drivers/adc_stm32f4xx.c \ drivers/bus_i2c_stm32f10x.c \ @@ -551,47 +527,6 @@ endif ifneq ($(filter ONBOARDFLASH,$(FEATURES)),) TARGET_SRC += \ -======= - drivers/accgyro_mpu3050.c \ - drivers/accgyro_mpu6050.c \ - drivers/accgyro_mpu6500.c \ - drivers/accgyro_spi_mpu6500.c \ - drivers/barometer_bmp085.c \ - drivers/barometer_bmp280.c \ - drivers/barometer_ms5611.c \ - drivers/compass_ak8975.c \ - drivers/compass_hmc5883l.c \ - drivers/compass_mag3110.c \ - drivers/flash_m25p16.c \ - drivers/light_ws2811strip.c \ - drivers/light_ws2811strip_stm32f10x.c \ - drivers/sonar_hcsr04.c \ - drivers/sonar_srf10.c \ - io/flashfs.c \ - hardware_revision.c \ - $(HIGHEND_SRC) \ - $(COMMON_SRC) - -ALIENFLIGHTF1_SRC = $(NAZE_SRC) - -EUSTM32F103RC_SRC = \ - $(STM32F10x_COMMON_SRC) \ - drivers/accgyro_adxl345.c \ - drivers/accgyro_bma280.c \ - drivers/accgyro_l3g4200d.c \ - drivers/accgyro_mma845x.c \ - drivers/accgyro_mpu.c \ - drivers/accgyro_mpu3050.c \ - drivers/accgyro_mpu6050.c \ - drivers/accgyro_spi_mpu6000.c \ - drivers/accgyro_spi_mpu6500.c \ - drivers/barometer_bmp085.c \ - drivers/barometer_bmp280.c \ - drivers/barometer_ms5611.c \ - drivers/compass_ak8975.c \ - drivers/compass_hmc5883l.c \ - drivers/compass_mag3110.c \ ->>>>>>> NRF24 support for iNav. drivers/flash_m25p16.c \ io/flashfs.c endif diff --git a/src/main/rx/nrf24.c b/src/main/rx/nrf24.c index 8e5cf2e73..5404147fa 100644 --- a/src/main/rx/nrf24.c +++ b/src/main/rx/nrf24.c @@ -29,6 +29,7 @@ #include "rx/nrf24_syma.h" #include "rx/nrf24_v202.h" #include "rx/nrf24_h8_3d.h" +#include "rx/nrf24_ref.h" uint16_t nrf24RcData[MAX_SUPPORTED_RC_CHANNEL_COUNT]; @@ -89,6 +90,13 @@ STATIC_UNIT_TESTED bool rxNrf24SetProtocol(nrf24_protocol_t protocol) protocolSetRcDataFromPayload = h8_3dSetRcDataFromPayload; break; #endif +#ifdef USE_RX_REF + case NRF24RX_REF: + protocolInit = refInit; + protocolDataReceived = refDataReceived; + protocolSetRcDataFromPayload = refSetRcDataFromPayload; + break; +#endif default: return false; break; diff --git a/src/main/rx/nrf24.h b/src/main/rx/nrf24.h index a1674fcb5..5156af15c 100644 --- a/src/main/rx/nrf24.h +++ b/src/main/rx/nrf24.h @@ -30,6 +30,7 @@ typedef enum { NRF24RX_CX10, NRF24RX_CX10A, NRF24RX_H8_3D, + NRF24RX_REF, NRF24RX_PROTOCOL_COUNT } nrf24_protocol_t; diff --git a/src/main/rx/nrf24_ref.c b/src/main/rx/nrf24_ref.c index 01ed5517b..2134e46da 100644 --- a/src/main/rx/nrf24_ref.c +++ b/src/main/rx/nrf24_ref.c @@ -28,7 +28,7 @@ #include "drivers/system.h" #include "rx/nrf24.h" -//#include "rx/nrf24_ref.h" +#include "rx/nrf24_ref.h" @@ -43,8 +43,17 @@ * uses channel 0x4c * * Data Phase - * uses address received in bind packet - * hops between 4 channels generated from address received in bind packet + * uses the address received in bind packet + * hops between 4 RF channels generated from the address received in bind packet + * + * There are 16 channels: eight 10-bit analog channels, two 8-bit analog channels, and six digital channels as follows: + * + * Channels 0 to 3, are the AETR channels, values 1000 to 2000 with resolution of 1 (10-bit channels) + * Channel AUX1 by deviation convention is used for rate, values 1000, 1500, 2000 + * Channels AUX2 to AUX6 are binary channels, values 1000 or 2000, + * by deviation convention used for flip, picture, video, headless, and return to home + * Channels AUX7 to AUX10 are analog channels, values 1000 to 2000 with resolution of 1 (10-bit channels) + * Channels AUX11 and AUX12 are analog channels, values 1000 to 2000 with resolution of 4 (8-bit channels) */ #define RC_CHANNEL_COUNT 16 diff --git a/src/main/rx/nrf24_ref.h b/src/main/rx/nrf24_ref.h new file mode 100644 index 000000000..f9a4ee45b --- /dev/null +++ b/src/main/rx/nrf24_ref.h @@ -0,0 +1,26 @@ +/* + * This file is part of Cleanflight. + * + * Cleanflight is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * Cleanflight is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with Cleanflight. If not, see . + */ + +#pragma once + +#include +#include + +void refInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig); +void refSetRcDataFromPayload(uint16_t *rcData, const uint8_t *payload); +nrf24_received_t refDataReceived(uint8_t *payload); + diff --git a/src/main/target/CC3D/CC3D_NRF24.mk b/src/main/target/CC3D/CC3D_NRF24.mk new file mode 100644 index 000000000..e69de29bb diff --git a/src/main/target/CC3D/CC3D_OPBL_NRF24.mk b/src/main/target/CC3D/CC3D_OPBL_NRF24.mk new file mode 100644 index 000000000..e69de29bb diff --git a/src/main/target/CC3D/target.h b/src/main/target/CC3D/target.h index a5b7b6f50..7a2641451 100644 --- a/src/main/target/CC3D/target.h +++ b/src/main/target/CC3D/target.h @@ -73,12 +73,6 @@ #define USE_VCP #define USE_USART1 #define USE_USART3 -#define USE_SOFTSERIAL1 -#define SERIAL_PORT_COUNT 4 - -#define SOFTSERIAL_1_TIMER TIM3 -#define SOFTSERIAL_1_TIMER_TX_HARDWARE 1 // PWM 2 -#define SOFTSERIAL_1_TIMER_RX_HARDWARE 2 // PWM 3 #define USART3_RX_PIN Pin_11 #define USART3_TX_PIN Pin_10 @@ -93,18 +87,18 @@ #define USE_I2C #define I2C_DEVICE (I2CDEV_2) // Flex port - SCL/PB10, SDA/PB11 +#if defined(CC3D_NRF24) || defined(CC3D_OPBL_NRF24) #define USE_RX_NRF24 -#ifdef USE_RX_NRF24 +#endif +#ifdef USE_RX_NRF24 #define DEFAULT_RX_FEATURE FEATURE_RX_NRF24 #define DEFAULT_FEATURES FEATURE_SOFTSPI #define USE_RX_SYMA -#ifdef CC3D_OPBL #define USE_RX_V202 #define USE_RX_CX10 #define USE_RX_H8_3D #define USE_RX_REF -#endif //#define NRF24_DEFAULT_PROTOCOL NRF24RX_SYMA_X5C //#define NRF24_DEFAULT_PROTOCOL NRF24RX_V202_1M #define NRF24_DEFAULT_PROTOCOL NRF24RX_H8_3D @@ -133,6 +127,17 @@ #define NRF24_MOSI_PIN GPIO_Pin_1 #define NRF24_MISO_GPIO GPIOB #define NRF24_MISO_PIN GPIO_Pin_0 + +#define SERIAL_PORT_COUNT 3 + +#else + +#define USE_SOFTSERIAL1 +#define SERIAL_PORT_COUNT 4 + +#define SOFTSERIAL_1_TIMER TIM3 +#define SOFTSERIAL_1_TIMER_TX_HARDWARE 1 // PWM 2 +#define SOFTSERIAL_1_TIMER_RX_HARDWARE 2 // PWM 3 #endif // USE_RX_NRF24 @@ -188,19 +193,28 @@ #undef TELEMETRY_SMARTPORT #ifdef CC3D_OPBL +#ifdef USE_RX_NRF24 +#define TARGET_MOTOR_COUNT 4 #undef USE_SERVOS +#endif #undef BLACKBOX #undef TELEMETRY #undef TELEMETRY_LTM +#endif + +#ifdef USE_RX_NRF24 +#define SKIP_RX_PWM_PPM +#define SKIP_RX_MSP #undef SERIAL_RX #undef SPEKTRUM_BIND +#undef TELEMETRY +#undef TELEMETRY_LTM +#ifndef CC3D_OPBL #define LED_STRIP -#ifdef USE_RX_NRF24 -#define SKIP_RX_PWM_PPM -#undef BLACKBOX #endif #endif + // DEBUG //#define HIL //#define USE_FAKE_MAG -- 2.11.4.GIT