mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-20 23:05:19 +03:00
Rebased
This commit is contained in:
commit
af3132d422
94 changed files with 1663 additions and 918 deletions
1
.gitignore
vendored
1
.gitignore
vendored
|
@ -13,6 +13,7 @@
|
||||||
obj/
|
obj/
|
||||||
patches/
|
patches/
|
||||||
startup_stm32f10x_md_gcc.s
|
startup_stm32f10x_md_gcc.s
|
||||||
|
.idea
|
||||||
|
|
||||||
# script-generated files
|
# script-generated files
|
||||||
docs/Manual.pdf
|
docs/Manual.pdf
|
||||||
|
|
9
Makefile
9
Makefile
|
@ -123,7 +123,7 @@ endif
|
||||||
-include $(ROOT)/src/main/target/$(BASE_TARGET)/target.mk
|
-include $(ROOT)/src/main/target/$(BASE_TARGET)/target.mk
|
||||||
|
|
||||||
F4_TARGETS = $(F405_TARGETS) $(F411_TARGETS)
|
F4_TARGETS = $(F405_TARGETS) $(F411_TARGETS)
|
||||||
F7_TARGETS = $(F7X5XE_TARGETS) $(F7X5XG_TARGETS) $(F7X5XI_TARGETS)
|
F7_TARGETS = $(F7X5XE_TARGETS) $(F7X5XG_TARGETS) $(F7X5XI_TARGETS) $(F7X6XG_TARGETS)
|
||||||
|
|
||||||
ifeq ($(filter $(TARGET),$(VALID_TARGETS)),)
|
ifeq ($(filter $(TARGET),$(VALID_TARGETS)),)
|
||||||
$(error Target '$(TARGET)' is not valid, must be one of $(VALID_TARGETS). Have you prepared a valid target.mk?)
|
$(error Target '$(TARGET)' is not valid, must be one of $(VALID_TARGETS). Have you prepared a valid target.mk?)
|
||||||
|
@ -136,7 +136,7 @@ endif
|
||||||
128K_TARGETS = $(F1_TARGETS)
|
128K_TARGETS = $(F1_TARGETS)
|
||||||
256K_TARGETS = $(F3_TARGETS)
|
256K_TARGETS = $(F3_TARGETS)
|
||||||
512K_TARGETS = $(F411_TARGETS) $(F7X5XE_TARGETS)
|
512K_TARGETS = $(F411_TARGETS) $(F7X5XE_TARGETS)
|
||||||
1024K_TARGETS = $(F405_TARGETS) $(F7X5XG_TARGETS)
|
1024K_TARGETS = $(F405_TARGETS) $(F7X5XG_TARGETS) $(F7X6XG_TARGETS)
|
||||||
2048K_TARGETS = $(F7X5XI_TARGETS)
|
2048K_TARGETS = $(F7X5XI_TARGETS)
|
||||||
|
|
||||||
# Configure default flash sizes for the targets (largest size specified gets hit first) if flash not specified already.
|
# Configure default flash sizes for the targets (largest size specified gets hit first) if flash not specified already.
|
||||||
|
@ -376,6 +376,9 @@ ARCH_FLAGS = -mthumb -mcpu=cortex-m7 -mfloat-abi=hard -mfpu=fpv5-sp-d16 -fs
|
||||||
ifeq ($(TARGET),$(filter $(TARGET),$(F7X5XG_TARGETS)))
|
ifeq ($(TARGET),$(filter $(TARGET),$(F7X5XG_TARGETS)))
|
||||||
DEVICE_FLAGS = -DSTM32F745xx -DUSE_HAL_DRIVER -D__FPU_PRESENT
|
DEVICE_FLAGS = -DSTM32F745xx -DUSE_HAL_DRIVER -D__FPU_PRESENT
|
||||||
LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f745.ld
|
LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f745.ld
|
||||||
|
else ifeq ($(TARGET),$(filter $(TARGET),$(F7X6XG_TARGETS)))
|
||||||
|
DEVICE_FLAGS = -DSTM32F746xx -DUSE_HAL_DRIVER -D__FPU_PRESENT
|
||||||
|
LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f746.ld
|
||||||
else
|
else
|
||||||
$(error Unknown MCU for F7 target)
|
$(error Unknown MCU for F7 target)
|
||||||
endif
|
endif
|
||||||
|
@ -593,7 +596,7 @@ HIGHEND_SRC = \
|
||||||
telemetry/smartport.c \
|
telemetry/smartport.c \
|
||||||
telemetry/ltm.c \
|
telemetry/ltm.c \
|
||||||
telemetry/mavlink.c \
|
telemetry/mavlink.c \
|
||||||
telemetry/esc_telemetry.c \
|
sensors/esc_sensor.c \
|
||||||
|
|
||||||
SPEED_OPTIMISED_SRC = \
|
SPEED_OPTIMISED_SRC = \
|
||||||
common/encoding.c \
|
common/encoding.c \
|
||||||
|
|
|
@ -59,7 +59,7 @@ typedef enum {
|
||||||
DEBUG_VELOCITY,
|
DEBUG_VELOCITY,
|
||||||
DEBUG_DTERM_FILTER,
|
DEBUG_DTERM_FILTER,
|
||||||
DEBUG_ANGLERATE,
|
DEBUG_ANGLERATE,
|
||||||
DEBUG_ESC_TELEMETRY,
|
DEBUG_ESC_SENSOR,
|
||||||
DEBUG_SCHEDULER,
|
DEBUG_SCHEDULER,
|
||||||
DEBUG_STACK,
|
DEBUG_STACK,
|
||||||
DEBUG_COUNT
|
DEBUG_COUNT
|
||||||
|
|
|
@ -51,6 +51,10 @@
|
||||||
#define FLASH_PAGE_SIZE ((uint32_t)0x40000)
|
#define FLASH_PAGE_SIZE ((uint32_t)0x40000)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#if defined(STM32F746xx)
|
||||||
|
#define FLASH_PAGE_SIZE ((uint32_t)0x40000)
|
||||||
|
#endif
|
||||||
|
|
||||||
#if defined(STM32F40_41xxx)
|
#if defined(STM32F40_41xxx)
|
||||||
#define FLASH_PAGE_SIZE ((uint32_t)0x20000)
|
#define FLASH_PAGE_SIZE ((uint32_t)0x20000)
|
||||||
#endif
|
#endif
|
||||||
|
@ -78,6 +82,8 @@
|
||||||
#define FLASH_PAGE_COUNT 3 // just to make calculations work
|
#define FLASH_PAGE_COUNT 3 // just to make calculations work
|
||||||
#elif defined (STM32F745xx)
|
#elif defined (STM32F745xx)
|
||||||
#define FLASH_PAGE_COUNT 4 // just to make calculations work
|
#define FLASH_PAGE_COUNT 4 // just to make calculations work
|
||||||
|
#elif defined (STM32F746xx)
|
||||||
|
#define FLASH_PAGE_COUNT 4 // just to make calculations work
|
||||||
#else
|
#else
|
||||||
#define FLASH_PAGE_COUNT ((FLASH_SIZE * 0x400) / FLASH_PAGE_SIZE)
|
#define FLASH_PAGE_COUNT ((FLASH_SIZE * 0x400) / FLASH_PAGE_SIZE)
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -31,6 +31,8 @@
|
||||||
#include "drivers/sonar_hcsr04.h"
|
#include "drivers/sonar_hcsr04.h"
|
||||||
#include "drivers/sdcard.h"
|
#include "drivers/sdcard.h"
|
||||||
#include "drivers/vcd.h"
|
#include "drivers/vcd.h"
|
||||||
|
#include "drivers/light_led.h"
|
||||||
|
#include "drivers/flash.h"
|
||||||
|
|
||||||
#include "fc/rc_controls.h"
|
#include "fc/rc_controls.h"
|
||||||
|
|
||||||
|
@ -90,10 +92,12 @@
|
||||||
#define beeperConfig(x) (&masterConfig.beeperConfig)
|
#define beeperConfig(x) (&masterConfig.beeperConfig)
|
||||||
#define sonarConfig(x) (&masterConfig.sonarConfig)
|
#define sonarConfig(x) (&masterConfig.sonarConfig)
|
||||||
#define ledStripConfig(x) (&masterConfig.ledStripConfig)
|
#define ledStripConfig(x) (&masterConfig.ledStripConfig)
|
||||||
|
#define statusLedConfig(x) (&masterConfig.statusLedConfig)
|
||||||
#define osdProfile(x) (&masterConfig.osdProfile)
|
#define osdProfile(x) (&masterConfig.osdProfile)
|
||||||
#define vcdProfile(x) (&masterConfig.vcdProfile)
|
#define vcdProfile(x) (&masterConfig.vcdProfile)
|
||||||
#define sdcardConfig(x) (&masterConfig.sdcardConfig)
|
#define sdcardConfig(x) (&masterConfig.sdcardConfig)
|
||||||
#define blackboxConfig(x) (&masterConfig.blackboxConfig)
|
#define blackboxConfig(x) (&masterConfig.blackboxConfig)
|
||||||
|
#define flashConfig(x) (&masterConfig.flashConfig)
|
||||||
|
|
||||||
|
|
||||||
// System-wide
|
// System-wide
|
||||||
|
@ -162,6 +166,8 @@ typedef struct master_s {
|
||||||
serialConfig_t serialConfig;
|
serialConfig_t serialConfig;
|
||||||
telemetryConfig_t telemetryConfig;
|
telemetryConfig_t telemetryConfig;
|
||||||
|
|
||||||
|
statusLedConfig_t statusLedConfig;
|
||||||
|
|
||||||
#ifdef USE_PPM
|
#ifdef USE_PPM
|
||||||
ppmConfig_t ppmConfig;
|
ppmConfig_t ppmConfig;
|
||||||
#endif
|
#endif
|
||||||
|
@ -226,6 +232,10 @@ typedef struct master_s {
|
||||||
blackboxConfig_t blackboxConfig;
|
blackboxConfig_t blackboxConfig;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#ifdef USE_FLASHFS
|
||||||
|
flashConfig_t flashConfig;
|
||||||
|
#endif
|
||||||
|
|
||||||
uint32_t beeper_off_flags;
|
uint32_t beeper_off_flags;
|
||||||
uint32_t preferred_beeper_off_flags;
|
uint32_t preferred_beeper_off_flags;
|
||||||
|
|
||||||
|
|
|
@ -56,27 +56,8 @@
|
||||||
#define ADXL345_RANGE_16G 0x03
|
#define ADXL345_RANGE_16G 0x03
|
||||||
#define ADXL345_FIFO_STREAM 0x80
|
#define ADXL345_FIFO_STREAM 0x80
|
||||||
|
|
||||||
static void adxl345Init(accDev_t *acc);
|
|
||||||
static bool adxl345Read(int16_t *accelData);
|
|
||||||
|
|
||||||
static bool useFifo = false;
|
static bool useFifo = false;
|
||||||
|
|
||||||
bool adxl345Detect(drv_adxl345_config_t *init, accDev_t *acc)
|
|
||||||
{
|
|
||||||
uint8_t sig = 0;
|
|
||||||
bool ack = i2cRead(MPU_I2C_INSTANCE, ADXL345_ADDRESS, 0x00, 1, &sig);
|
|
||||||
|
|
||||||
if (!ack || sig != 0xE5)
|
|
||||||
return false;
|
|
||||||
|
|
||||||
// use ADXL345's fifo to filter data or not
|
|
||||||
useFifo = init->useFifo;
|
|
||||||
|
|
||||||
acc->init = adxl345Init;
|
|
||||||
acc->read = adxl345Read;
|
|
||||||
return true;
|
|
||||||
}
|
|
||||||
|
|
||||||
static void adxl345Init(accDev_t *acc)
|
static void adxl345Init(accDev_t *acc)
|
||||||
{
|
{
|
||||||
if (useFifo) {
|
if (useFifo) {
|
||||||
|
@ -135,3 +116,19 @@ static bool adxl345Read(int16_t *accelData)
|
||||||
|
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
bool adxl345Detect(drv_adxl345_config_t *init, accDev_t *acc)
|
||||||
|
{
|
||||||
|
uint8_t sig = 0;
|
||||||
|
bool ack = i2cRead(MPU_I2C_INSTANCE, ADXL345_ADDRESS, 0x00, 1, &sig);
|
||||||
|
|
||||||
|
if (!ack || sig != 0xE5)
|
||||||
|
return false;
|
||||||
|
|
||||||
|
// use ADXL345's fifo to filter data or not
|
||||||
|
useFifo = init->useFifo;
|
||||||
|
|
||||||
|
acc->init = adxl345Init;
|
||||||
|
acc->read = adxl345Read;
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
|
@ -32,22 +32,6 @@
|
||||||
#define BMA280_PMU_BW 0x10
|
#define BMA280_PMU_BW 0x10
|
||||||
#define BMA280_PMU_RANGE 0x0F
|
#define BMA280_PMU_RANGE 0x0F
|
||||||
|
|
||||||
static void bma280Init(accDev_t *acc);
|
|
||||||
static bool bma280Read(int16_t *accelData);
|
|
||||||
|
|
||||||
bool bma280Detect(accDev_t *acc)
|
|
||||||
{
|
|
||||||
uint8_t sig = 0;
|
|
||||||
bool ack = i2cRead(MPU_I2C_INSTANCE, BMA280_ADDRESS, 0x00, 1, &sig);
|
|
||||||
|
|
||||||
if (!ack || sig != 0xFB)
|
|
||||||
return false;
|
|
||||||
|
|
||||||
acc->init = bma280Init;
|
|
||||||
acc->read = bma280Read;
|
|
||||||
return true;
|
|
||||||
}
|
|
||||||
|
|
||||||
static void bma280Init(accDev_t *acc)
|
static void bma280Init(accDev_t *acc)
|
||||||
{
|
{
|
||||||
i2cWrite(MPU_I2C_INSTANCE, BMA280_ADDRESS, BMA280_PMU_RANGE, 0x08); // +-8g range
|
i2cWrite(MPU_I2C_INSTANCE, BMA280_ADDRESS, BMA280_PMU_RANGE, 0x08); // +-8g range
|
||||||
|
@ -71,3 +55,16 @@ static bool bma280Read(int16_t *accelData)
|
||||||
|
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
bool bma280Detect(accDev_t *acc)
|
||||||
|
{
|
||||||
|
uint8_t sig = 0;
|
||||||
|
bool ack = i2cRead(MPU_I2C_INSTANCE, BMA280_ADDRESS, 0x00, 1, &sig);
|
||||||
|
|
||||||
|
if (!ack || sig != 0xFB)
|
||||||
|
return false;
|
||||||
|
|
||||||
|
acc->init = bma280Init;
|
||||||
|
acc->read = bma280Read;
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
|
@ -54,28 +54,6 @@
|
||||||
#define L3G4200D_DLPF_78HZ 0x80
|
#define L3G4200D_DLPF_78HZ 0x80
|
||||||
#define L3G4200D_DLPF_93HZ 0xC0
|
#define L3G4200D_DLPF_93HZ 0xC0
|
||||||
|
|
||||||
static void l3g4200dInit(gyroDev_t *gyro);
|
|
||||||
static bool l3g4200dRead(gyroDev_t *gyro);
|
|
||||||
|
|
||||||
bool l3g4200dDetect(gyroDev_t *gyro)
|
|
||||||
{
|
|
||||||
uint8_t deviceid;
|
|
||||||
|
|
||||||
delay(25);
|
|
||||||
|
|
||||||
i2cRead(MPU_I2C_INSTANCE, L3G4200D_ADDRESS, L3G4200D_WHO_AM_I, 1, &deviceid);
|
|
||||||
if (deviceid != L3G4200D_ID)
|
|
||||||
return false;
|
|
||||||
|
|
||||||
gyro->init = l3g4200dInit;
|
|
||||||
gyro->read = l3g4200dRead;
|
|
||||||
|
|
||||||
// 14.2857dps/lsb scalefactor
|
|
||||||
gyro->scale = 1.0f / 14.2857f;
|
|
||||||
|
|
||||||
return true;
|
|
||||||
}
|
|
||||||
|
|
||||||
static void l3g4200dInit(gyroDev_t *gyro)
|
static void l3g4200dInit(gyroDev_t *gyro)
|
||||||
{
|
{
|
||||||
bool ack;
|
bool ack;
|
||||||
|
@ -123,3 +101,22 @@ static bool l3g4200dRead(gyroDev_t *gyro)
|
||||||
|
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
bool l3g4200dDetect(gyroDev_t *gyro)
|
||||||
|
{
|
||||||
|
uint8_t deviceid;
|
||||||
|
|
||||||
|
delay(25);
|
||||||
|
|
||||||
|
i2cRead(MPU_I2C_INSTANCE, L3G4200D_ADDRESS, L3G4200D_WHO_AM_I, 1, &deviceid);
|
||||||
|
if (deviceid != L3G4200D_ID)
|
||||||
|
return false;
|
||||||
|
|
||||||
|
gyro->init = l3g4200dInit;
|
||||||
|
gyro->read = l3g4200dRead;
|
||||||
|
|
||||||
|
// 14.2857dps/lsb scalefactor
|
||||||
|
gyro->scale = 1.0f / 14.2857f;
|
||||||
|
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
|
@ -81,23 +81,6 @@
|
||||||
|
|
||||||
static uint8_t device_id;
|
static uint8_t device_id;
|
||||||
|
|
||||||
static void mma8452Init(accDev_t *acc);
|
|
||||||
static bool mma8452Read(int16_t *accelData);
|
|
||||||
|
|
||||||
bool mma8452Detect(accDev_t *acc)
|
|
||||||
{
|
|
||||||
uint8_t sig = 0;
|
|
||||||
bool ack = i2cRead(MPU_I2C_INSTANCE, MMA8452_ADDRESS, MMA8452_WHO_AM_I, 1, &sig);
|
|
||||||
|
|
||||||
if (!ack || (sig != MMA8452_DEVICE_SIGNATURE && sig != MMA8451_DEVICE_SIGNATURE))
|
|
||||||
return false;
|
|
||||||
|
|
||||||
acc->init = mma8452Init;
|
|
||||||
acc->read = mma8452Read;
|
|
||||||
device_id = sig;
|
|
||||||
return true;
|
|
||||||
}
|
|
||||||
|
|
||||||
static inline void mma8451ConfigureInterrupt(void)
|
static inline void mma8451ConfigureInterrupt(void)
|
||||||
{
|
{
|
||||||
#ifdef NAZE
|
#ifdef NAZE
|
||||||
|
@ -142,3 +125,17 @@ static bool mma8452Read(int16_t *accelData)
|
||||||
|
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
bool mma8452Detect(accDev_t *acc)
|
||||||
|
{
|
||||||
|
uint8_t sig = 0;
|
||||||
|
bool ack = i2cRead(MPU_I2C_INSTANCE, MMA8452_ADDRESS, MMA8452_WHO_AM_I, 1, &sig);
|
||||||
|
|
||||||
|
if (!ack || (sig != MMA8452_DEVICE_SIGNATURE && sig != MMA8451_DEVICE_SIGNATURE))
|
||||||
|
return false;
|
||||||
|
|
||||||
|
acc->init = mma8452Init;
|
||||||
|
acc->read = mma8452Read;
|
||||||
|
device_id = sig;
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
|
@ -75,7 +75,7 @@ static const extiConfig_t *mpuIntExtiConfig = NULL;
|
||||||
|
|
||||||
#define MPU_INQUIRY_MASK 0x7E
|
#define MPU_INQUIRY_MASK 0x7E
|
||||||
|
|
||||||
mpuDetectionResult_t *detectMpu(const extiConfig_t *configToUse)
|
mpuDetectionResult_t *mpuDetect(const extiConfig_t *configToUse)
|
||||||
{
|
{
|
||||||
memset(&mpuDetectionResult, 0, sizeof(mpuDetectionResult));
|
memset(&mpuDetectionResult, 0, sizeof(mpuDetectionResult));
|
||||||
memset(&mpuConfiguration, 0, sizeof(mpuConfiguration));
|
memset(&mpuConfiguration, 0, sizeof(mpuConfiguration));
|
||||||
|
@ -334,7 +334,7 @@ void mpuGyroInit(gyroDev_t *gyro)
|
||||||
mpuIntExtiInit(gyro);
|
mpuIntExtiInit(gyro);
|
||||||
}
|
}
|
||||||
|
|
||||||
bool checkMPUDataReady(gyroDev_t* gyro)
|
bool mpuCheckDataReady(gyroDev_t* gyro)
|
||||||
{
|
{
|
||||||
bool ret;
|
bool ret;
|
||||||
if (gyro->dataReady) {
|
if (gyro->dataReady) {
|
||||||
|
|
|
@ -183,10 +183,10 @@ typedef struct mpuDetectionResult_s {
|
||||||
|
|
||||||
extern mpuDetectionResult_t mpuDetectionResult;
|
extern mpuDetectionResult_t mpuDetectionResult;
|
||||||
|
|
||||||
void configureMPUDataReadyInterruptHandling(void);
|
void mpuConfigureDataReadyInterruptHandling(void);
|
||||||
struct gyroDev_s;
|
struct gyroDev_s;
|
||||||
void mpuGyroInit(struct gyroDev_s *gyro);
|
void mpuGyroInit(struct gyroDev_s *gyro);
|
||||||
bool mpuAccRead(int16_t *accData);
|
bool mpuAccRead(int16_t *accData);
|
||||||
bool mpuGyroRead(struct gyroDev_s *gyro);
|
bool mpuGyroRead(struct gyroDev_s *gyro);
|
||||||
mpuDetectionResult_t *detectMpu(const extiConfig_t *configToUse);
|
mpuDetectionResult_t *mpuDetect(const extiConfig_t *configToUse);
|
||||||
bool checkMPUDataReady(struct gyroDev_s *gyro);
|
bool mpuCheckDataReady(struct gyroDev_s *gyro);
|
||||||
|
|
|
@ -46,25 +46,6 @@
|
||||||
#define MPU3050_USER_RESET 0x01
|
#define MPU3050_USER_RESET 0x01
|
||||||
#define MPU3050_CLK_SEL_PLL_GX 0x01
|
#define MPU3050_CLK_SEL_PLL_GX 0x01
|
||||||
|
|
||||||
static void mpu3050Init(gyroDev_t *gyro);
|
|
||||||
static bool mpu3050ReadTemp(int16_t *tempData);
|
|
||||||
|
|
||||||
bool mpu3050Detect(gyroDev_t *gyro)
|
|
||||||
{
|
|
||||||
if (mpuDetectionResult.sensor != MPU_3050) {
|
|
||||||
return false;
|
|
||||||
}
|
|
||||||
gyro->init = mpu3050Init;
|
|
||||||
gyro->read = mpuGyroRead;
|
|
||||||
gyro->temperature = mpu3050ReadTemp;
|
|
||||||
gyro->intStatus = checkMPUDataReady;
|
|
||||||
|
|
||||||
// 16.4 dps/lsb scalefactor
|
|
||||||
gyro->scale = 1.0f / 16.4f;
|
|
||||||
|
|
||||||
return true;
|
|
||||||
}
|
|
||||||
|
|
||||||
static void mpu3050Init(gyroDev_t *gyro)
|
static void mpu3050Init(gyroDev_t *gyro)
|
||||||
{
|
{
|
||||||
bool ack;
|
bool ack;
|
||||||
|
@ -81,7 +62,7 @@ static void mpu3050Init(gyroDev_t *gyro)
|
||||||
mpuConfiguration.write(MPU3050_PWR_MGM, MPU3050_CLK_SEL_PLL_GX);
|
mpuConfiguration.write(MPU3050_PWR_MGM, MPU3050_CLK_SEL_PLL_GX);
|
||||||
}
|
}
|
||||||
|
|
||||||
static bool mpu3050ReadTemp(int16_t *tempData)
|
static bool mpu3050ReadTemperature(int16_t *tempData)
|
||||||
{
|
{
|
||||||
uint8_t buf[2];
|
uint8_t buf[2];
|
||||||
if (!mpuConfiguration.read(MPU3050_TEMP_OUT, 2, buf)) {
|
if (!mpuConfiguration.read(MPU3050_TEMP_OUT, 2, buf)) {
|
||||||
|
@ -92,3 +73,19 @@ static bool mpu3050ReadTemp(int16_t *tempData)
|
||||||
|
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
bool mpu3050Detect(gyroDev_t *gyro)
|
||||||
|
{
|
||||||
|
if (mpuDetectionResult.sensor != MPU_3050) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
gyro->init = mpu3050Init;
|
||||||
|
gyro->read = mpuGyroRead;
|
||||||
|
gyro->temperature = mpu3050ReadTemperature;
|
||||||
|
gyro->intStatus = mpuCheckDataReady;
|
||||||
|
|
||||||
|
// 16.4 dps/lsb scalefactor
|
||||||
|
gyro->scale = 1.0f / 16.4f;
|
||||||
|
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
|
@ -50,8 +50,17 @@
|
||||||
|
|
||||||
#define MPU6050_SMPLRT_DIV 0 // 8000Hz
|
#define MPU6050_SMPLRT_DIV 0 // 8000Hz
|
||||||
|
|
||||||
static void mpu6050AccInit(accDev_t *acc);
|
static void mpu6050AccInit(accDev_t *acc)
|
||||||
static void mpu6050GyroInit(gyroDev_t *gyro);
|
{
|
||||||
|
switch (mpuDetectionResult.resolution) {
|
||||||
|
case MPU_HALF_RESOLUTION:
|
||||||
|
acc->acc_1G = 256 * 4;
|
||||||
|
break;
|
||||||
|
case MPU_FULL_RESOLUTION:
|
||||||
|
acc->acc_1G = 512 * 4;
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
bool mpu6050AccDetect(accDev_t *acc)
|
bool mpu6050AccDetect(accDev_t *acc)
|
||||||
{
|
{
|
||||||
|
@ -66,33 +75,6 @@ bool mpu6050AccDetect(accDev_t *acc)
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
bool mpu6050GyroDetect(gyroDev_t *gyro)
|
|
||||||
{
|
|
||||||
if (mpuDetectionResult.sensor != MPU_60x0) {
|
|
||||||
return false;
|
|
||||||
}
|
|
||||||
gyro->init = mpu6050GyroInit;
|
|
||||||
gyro->read = mpuGyroRead;
|
|
||||||
gyro->intStatus = checkMPUDataReady;
|
|
||||||
|
|
||||||
// 16.4 dps/lsb scalefactor
|
|
||||||
gyro->scale = 1.0f / 16.4f;
|
|
||||||
|
|
||||||
return true;
|
|
||||||
}
|
|
||||||
|
|
||||||
static void mpu6050AccInit(accDev_t *acc)
|
|
||||||
{
|
|
||||||
switch (mpuDetectionResult.resolution) {
|
|
||||||
case MPU_HALF_RESOLUTION:
|
|
||||||
acc->acc_1G = 256 * 4;
|
|
||||||
break;
|
|
||||||
case MPU_FULL_RESOLUTION:
|
|
||||||
acc->acc_1G = 512 * 4;
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
static void mpu6050GyroInit(gyroDev_t *gyro)
|
static void mpu6050GyroInit(gyroDev_t *gyro)
|
||||||
{
|
{
|
||||||
mpuGyroInit(gyro);
|
mpuGyroInit(gyro);
|
||||||
|
@ -116,3 +98,18 @@ static void mpu6050GyroInit(gyroDev_t *gyro)
|
||||||
mpuConfiguration.write(MPU_RA_INT_ENABLE, MPU_RF_DATA_RDY_EN);
|
mpuConfiguration.write(MPU_RA_INT_ENABLE, MPU_RF_DATA_RDY_EN);
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
|
bool mpu6050GyroDetect(gyroDev_t *gyro)
|
||||||
|
{
|
||||||
|
if (mpuDetectionResult.sensor != MPU_60x0) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
gyro->init = mpu6050GyroInit;
|
||||||
|
gyro->read = mpuGyroRead;
|
||||||
|
gyro->intStatus = mpuCheckDataReady;
|
||||||
|
|
||||||
|
// 16.4 dps/lsb scalefactor
|
||||||
|
gyro->scale = 1.0f / 16.4f;
|
||||||
|
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
|
@ -34,6 +34,11 @@
|
||||||
#include "accgyro_mpu.h"
|
#include "accgyro_mpu.h"
|
||||||
#include "accgyro_mpu6500.h"
|
#include "accgyro_mpu6500.h"
|
||||||
|
|
||||||
|
void mpu6500AccInit(accDev_t *acc)
|
||||||
|
{
|
||||||
|
acc->acc_1G = 512 * 4;
|
||||||
|
}
|
||||||
|
|
||||||
bool mpu6500AccDetect(accDev_t *acc)
|
bool mpu6500AccDetect(accDev_t *acc)
|
||||||
{
|
{
|
||||||
if (mpuDetectionResult.sensor != MPU_65xx_I2C) {
|
if (mpuDetectionResult.sensor != MPU_65xx_I2C) {
|
||||||
|
@ -46,27 +51,6 @@ bool mpu6500AccDetect(accDev_t *acc)
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
bool mpu6500GyroDetect(gyroDev_t *gyro)
|
|
||||||
{
|
|
||||||
if (mpuDetectionResult.sensor != MPU_65xx_I2C) {
|
|
||||||
return false;
|
|
||||||
}
|
|
||||||
|
|
||||||
gyro->init = mpu6500GyroInit;
|
|
||||||
gyro->read = mpuGyroRead;
|
|
||||||
gyro->intStatus = checkMPUDataReady;
|
|
||||||
|
|
||||||
// 16.4 dps/lsb scalefactor
|
|
||||||
gyro->scale = 1.0f / 16.4f;
|
|
||||||
|
|
||||||
return true;
|
|
||||||
}
|
|
||||||
|
|
||||||
void mpu6500AccInit(accDev_t *acc)
|
|
||||||
{
|
|
||||||
acc->acc_1G = 512 * 4;
|
|
||||||
}
|
|
||||||
|
|
||||||
void mpu6500GyroInit(gyroDev_t *gyro)
|
void mpu6500GyroInit(gyroDev_t *gyro)
|
||||||
{
|
{
|
||||||
mpuGyroInit(gyro);
|
mpuGyroInit(gyro);
|
||||||
|
@ -101,3 +85,19 @@ void mpu6500GyroInit(gyroDev_t *gyro)
|
||||||
#endif
|
#endif
|
||||||
delay(15);
|
delay(15);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
bool mpu6500GyroDetect(gyroDev_t *gyro)
|
||||||
|
{
|
||||||
|
if (mpuDetectionResult.sensor != MPU_65xx_I2C) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
gyro->init = mpu6500GyroInit;
|
||||||
|
gyro->read = mpuGyroRead;
|
||||||
|
gyro->intStatus = mpuCheckDataReady;
|
||||||
|
|
||||||
|
// 16.4 dps/lsb scalefactor
|
||||||
|
gyro->scale = 1.0f / 16.4f;
|
||||||
|
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
|
@ -107,6 +107,11 @@ bool icm20689SpiDetect(void)
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void icm20689AccInit(accDev_t *acc)
|
||||||
|
{
|
||||||
|
acc->acc_1G = 512 * 4;
|
||||||
|
}
|
||||||
|
|
||||||
bool icm20689SpiAccDetect(accDev_t *acc)
|
bool icm20689SpiAccDetect(accDev_t *acc)
|
||||||
{
|
{
|
||||||
if (mpuDetectionResult.sensor != ICM_20689_SPI) {
|
if (mpuDetectionResult.sensor != ICM_20689_SPI) {
|
||||||
|
@ -119,27 +124,6 @@ bool icm20689SpiAccDetect(accDev_t *acc)
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
bool icm20689SpiGyroDetect(gyroDev_t *gyro)
|
|
||||||
{
|
|
||||||
if (mpuDetectionResult.sensor != ICM_20689_SPI) {
|
|
||||||
return false;
|
|
||||||
}
|
|
||||||
|
|
||||||
gyro->init = icm20689GyroInit;
|
|
||||||
gyro->read = mpuGyroRead;
|
|
||||||
gyro->intStatus = checkMPUDataReady;
|
|
||||||
|
|
||||||
// 16.4 dps/lsb scalefactor
|
|
||||||
gyro->scale = 1.0f / 16.4f;
|
|
||||||
|
|
||||||
return true;
|
|
||||||
}
|
|
||||||
|
|
||||||
void icm20689AccInit(accDev_t *acc)
|
|
||||||
{
|
|
||||||
acc->acc_1G = 512 * 4;
|
|
||||||
}
|
|
||||||
|
|
||||||
void icm20689GyroInit(gyroDev_t *gyro)
|
void icm20689GyroInit(gyroDev_t *gyro)
|
||||||
{
|
{
|
||||||
mpuGyroInit(gyro);
|
mpuGyroInit(gyro);
|
||||||
|
@ -174,5 +158,20 @@ void icm20689GyroInit(gyroDev_t *gyro)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
spiSetDivisor(ICM20689_SPI_INSTANCE, SPI_CLOCK_STANDARD);
|
spiSetDivisor(ICM20689_SPI_INSTANCE, SPI_CLOCK_STANDARD);
|
||||||
|
}
|
||||||
|
|
||||||
|
bool icm20689SpiGyroDetect(gyroDev_t *gyro)
|
||||||
|
{
|
||||||
|
if (mpuDetectionResult.sensor != ICM_20689_SPI) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
gyro->init = icm20689GyroInit;
|
||||||
|
gyro->read = mpuGyroRead;
|
||||||
|
gyro->intStatus = mpuCheckDataReady;
|
||||||
|
|
||||||
|
// 16.4 dps/lsb scalefactor
|
||||||
|
gyro->scale = 1.0f / 16.4f;
|
||||||
|
|
||||||
|
return true;
|
||||||
}
|
}
|
||||||
|
|
|
@ -274,7 +274,7 @@ bool mpu6000SpiGyroDetect(gyroDev_t *gyro)
|
||||||
|
|
||||||
gyro->init = mpu6000SpiGyroInit;
|
gyro->init = mpu6000SpiGyroInit;
|
||||||
gyro->read = mpuGyroRead;
|
gyro->read = mpuGyroRead;
|
||||||
gyro->intStatus = checkMPUDataReady;
|
gyro->intStatus = mpuCheckDataReady;
|
||||||
// 16.4 dps/lsb scalefactor
|
// 16.4 dps/lsb scalefactor
|
||||||
gyro->scale = 1.0f / 16.4f;
|
gyro->scale = 1.0f / 16.4f;
|
||||||
|
|
||||||
|
|
|
@ -134,7 +134,7 @@ bool mpu6500SpiGyroDetect(gyroDev_t *gyro)
|
||||||
|
|
||||||
gyro->init = mpu6500SpiGyroInit;
|
gyro->init = mpu6500SpiGyroInit;
|
||||||
gyro->read = mpuGyroRead;
|
gyro->read = mpuGyroRead;
|
||||||
gyro->intStatus = checkMPUDataReady;
|
gyro->intStatus = mpuCheckDataReady;
|
||||||
|
|
||||||
// 16.4 dps/lsb scalefactor
|
// 16.4 dps/lsb scalefactor
|
||||||
gyro->scale = 1.0f / 16.4f;
|
gyro->scale = 1.0f / 16.4f;
|
||||||
|
|
|
@ -229,7 +229,7 @@ bool mpu9250SpiGyroDetect(gyroDev_t *gyro)
|
||||||
|
|
||||||
gyro->init = mpu9250SpiGyroInit;
|
gyro->init = mpu9250SpiGyroInit;
|
||||||
gyro->read = mpuGyroRead;
|
gyro->read = mpuGyroRead;
|
||||||
gyro->intStatus = checkMPUDataReady;
|
gyro->intStatus = mpuCheckDataReady;
|
||||||
|
|
||||||
// 16.4 dps/lsb scalefactor
|
// 16.4 dps/lsb scalefactor
|
||||||
gyro->scale = 1.0f / 16.4f;
|
gyro->scale = 1.0f / 16.4f;
|
||||||
|
|
|
@ -18,6 +18,7 @@
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
#include <stdint.h>
|
#include <stdint.h>
|
||||||
|
#include "drivers/io_types.h"
|
||||||
|
|
||||||
typedef struct flashGeometry_s {
|
typedef struct flashGeometry_s {
|
||||||
uint16_t sectors; // Count of the number of erasable blocks on the device
|
uint16_t sectors; // Count of the number of erasable blocks on the device
|
||||||
|
@ -29,3 +30,7 @@ typedef struct flashGeometry_s {
|
||||||
|
|
||||||
uint32_t totalSize; // This is just sectorSize * sectors
|
uint32_t totalSize; // This is just sectorSize * sectors
|
||||||
} flashGeometry_t;
|
} flashGeometry_t;
|
||||||
|
|
||||||
|
typedef struct flashConfig_s {
|
||||||
|
ioTag_t csTag;
|
||||||
|
} flashConfig_t;
|
||||||
|
|
|
@ -208,27 +208,21 @@ static bool m25p16_readIdentification()
|
||||||
* Attempts to detect a connected m25p16. If found, true is returned and device capacity can be fetched with
|
* Attempts to detect a connected m25p16. If found, true is returned and device capacity can be fetched with
|
||||||
* m25p16_getGeometry().
|
* m25p16_getGeometry().
|
||||||
*/
|
*/
|
||||||
bool m25p16_init(ioTag_t csTag)
|
bool m25p16_init(flashConfig_t *flashConfig)
|
||||||
{
|
{
|
||||||
/*
|
/*
|
||||||
if we have already detected a flash device we can simply exit
|
if we have already detected a flash device we can simply exit
|
||||||
|
|
||||||
TODO: change the init param in favour of flash CFG when ParamGroups work is done
|
|
||||||
then cs pin can be specified in hardware_revision.c or config.c (dependent on revision).
|
|
||||||
*/
|
*/
|
||||||
if (geometry.sectors) {
|
if (geometry.sectors) {
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (csTag) {
|
if (flashConfig->csTag) {
|
||||||
m25p16CsPin = IOGetByTag(csTag);
|
m25p16CsPin = IOGetByTag(flashConfig->csTag);
|
||||||
} else {
|
} else {
|
||||||
#ifdef M25P16_CS_PIN
|
|
||||||
m25p16CsPin = IOGetByTag(IO_TAG(M25P16_CS_PIN));
|
|
||||||
#else
|
|
||||||
return false;
|
return false;
|
||||||
#endif
|
|
||||||
}
|
}
|
||||||
|
|
||||||
IOInit(m25p16CsPin, OWNER_FLASH_CS, 0);
|
IOInit(m25p16CsPin, OWNER_FLASH_CS, 0);
|
||||||
IOConfigGPIO(m25p16CsPin, SPI_IO_CS_CFG);
|
IOConfigGPIO(m25p16CsPin, SPI_IO_CS_CFG);
|
||||||
|
|
||||||
|
|
|
@ -18,11 +18,11 @@
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
#include <stdint.h>
|
#include <stdint.h>
|
||||||
#include "io_types.h"
|
#include "flash.h"
|
||||||
|
|
||||||
#define M25P16_PAGESIZE 256
|
#define M25P16_PAGESIZE 256
|
||||||
|
|
||||||
bool m25p16_init(ioTag_t csTag);
|
bool m25p16_init(flashConfig_t *flashConfig);
|
||||||
|
|
||||||
void m25p16_eraseSector(uint32_t address);
|
void m25p16_eraseSector(uint32_t address);
|
||||||
void m25p16_eraseCompletely();
|
void m25p16_eraseCompletely();
|
||||||
|
|
|
@ -22,82 +22,23 @@
|
||||||
|
|
||||||
#include "light_led.h"
|
#include "light_led.h"
|
||||||
|
|
||||||
static const IO_t leds[] = {
|
static IO_t leds[LED_NUMBER];
|
||||||
#ifdef LED0
|
static uint8_t ledPolarity = 0;
|
||||||
DEFIO_IO(LED0),
|
|
||||||
#else
|
|
||||||
DEFIO_IO(NONE),
|
|
||||||
#endif
|
|
||||||
#ifdef LED1
|
|
||||||
DEFIO_IO(LED1),
|
|
||||||
#else
|
|
||||||
DEFIO_IO(NONE),
|
|
||||||
#endif
|
|
||||||
#ifdef LED2
|
|
||||||
DEFIO_IO(LED2),
|
|
||||||
#else
|
|
||||||
DEFIO_IO(NONE),
|
|
||||||
#endif
|
|
||||||
#if defined(LED0_A) || defined(LED1_A) || defined(LED2_A)
|
|
||||||
#ifdef LED0_A
|
|
||||||
DEFIO_IO(LED0_A),
|
|
||||||
#else
|
|
||||||
DEFIO_IO(NONE),
|
|
||||||
#endif
|
|
||||||
#ifdef LED1_A
|
|
||||||
DEFIO_IO(LED1_A),
|
|
||||||
#else
|
|
||||||
DEFIO_IO(NONE),
|
|
||||||
#endif
|
|
||||||
#ifdef LED2_A
|
|
||||||
DEFIO_IO(LED2_A),
|
|
||||||
#else
|
|
||||||
DEFIO_IO(NONE),
|
|
||||||
#endif
|
|
||||||
#endif
|
|
||||||
};
|
|
||||||
|
|
||||||
uint8_t ledPolarity = 0
|
void ledInit(statusLedConfig_t *statusLedConfig)
|
||||||
#ifdef LED0_INVERTED
|
|
||||||
| BIT(0)
|
|
||||||
#endif
|
|
||||||
#ifdef LED1_INVERTED
|
|
||||||
| BIT(1)
|
|
||||||
#endif
|
|
||||||
#ifdef LED2_INVERTED
|
|
||||||
| BIT(2)
|
|
||||||
#endif
|
|
||||||
#ifdef LED0_A_INVERTED
|
|
||||||
| BIT(3)
|
|
||||||
#endif
|
|
||||||
#ifdef LED1_A_INVERTED
|
|
||||||
| BIT(4)
|
|
||||||
#endif
|
|
||||||
#ifdef LED2_A_INVERTED
|
|
||||||
| BIT(5)
|
|
||||||
#endif
|
|
||||||
;
|
|
||||||
|
|
||||||
static uint8_t ledOffset = 0;
|
|
||||||
|
|
||||||
void ledInit(bool alternative_led)
|
|
||||||
{
|
{
|
||||||
#if defined(LED0_A) || defined(LED1_A) || defined(LED2_A)
|
|
||||||
if (alternative_led) {
|
|
||||||
ledOffset = LED_NUMBER;
|
|
||||||
}
|
|
||||||
#else
|
|
||||||
UNUSED(alternative_led);
|
|
||||||
#endif
|
|
||||||
|
|
||||||
LED0_OFF;
|
LED0_OFF;
|
||||||
LED1_OFF;
|
LED1_OFF;
|
||||||
LED2_OFF;
|
LED2_OFF;
|
||||||
|
|
||||||
|
ledPolarity = statusLedConfig->polarity;
|
||||||
for (int i = 0; i < LED_NUMBER; i++) {
|
for (int i = 0; i < LED_NUMBER; i++) {
|
||||||
if (leds[i + ledOffset]) {
|
if (statusLedConfig->ledTags[i]) {
|
||||||
IOInit(leds[i + ledOffset], OWNER_LED, RESOURCE_INDEX(i));
|
leds[i] = IOGetByTag(statusLedConfig->ledTags[i]);
|
||||||
IOConfigGPIO(leds[i + ledOffset], IOCFG_OUT_PP);
|
IOInit(leds[i], OWNER_LED, RESOURCE_INDEX(i));
|
||||||
|
IOConfigGPIO(leds[i], IOCFG_OUT_PP);
|
||||||
|
} else {
|
||||||
|
leds[i] = IO_NONE;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -108,11 +49,11 @@ void ledInit(bool alternative_led)
|
||||||
|
|
||||||
void ledToggle(int led)
|
void ledToggle(int led)
|
||||||
{
|
{
|
||||||
IOToggle(leds[led + ledOffset]);
|
IOToggle(leds[led]);
|
||||||
}
|
}
|
||||||
|
|
||||||
void ledSet(int led, bool on)
|
void ledSet(int led, bool on)
|
||||||
{
|
{
|
||||||
const bool inverted = (1 << (led + ledOffset)) & ledPolarity;
|
const bool inverted = (1 << (led)) & ledPolarity;
|
||||||
IOWrite(leds[led + ledOffset], on ? inverted : !inverted);
|
IOWrite(leds[led], on ? inverted : !inverted);
|
||||||
}
|
}
|
||||||
|
|
|
@ -17,8 +17,15 @@
|
||||||
|
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
|
#include "drivers/io_types.h"
|
||||||
|
|
||||||
#define LED_NUMBER 3
|
#define LED_NUMBER 3
|
||||||
|
|
||||||
|
typedef struct statusLedConfig_s {
|
||||||
|
ioTag_t ledTags[LED_NUMBER];
|
||||||
|
uint8_t polarity;
|
||||||
|
} statusLedConfig_t;
|
||||||
|
|
||||||
// Helpful macros
|
// Helpful macros
|
||||||
#ifdef LED0
|
#ifdef LED0
|
||||||
# define LED0_TOGGLE ledToggle(0)
|
# define LED0_TOGGLE ledToggle(0)
|
||||||
|
@ -50,6 +57,6 @@
|
||||||
# define LED2_ON do {} while(0)
|
# define LED2_ON do {} while(0)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
void ledInit(bool alternative_led);
|
void ledInit(statusLedConfig_t *statusLedConfig);
|
||||||
void ledToggle(int led);
|
void ledToggle(int led);
|
||||||
void ledSet(int led, bool state);
|
void ledSet(int led, bool state);
|
||||||
|
|
|
@ -24,6 +24,7 @@
|
||||||
#include "io.h"
|
#include "io.h"
|
||||||
#include "timer.h"
|
#include "timer.h"
|
||||||
#include "pwm_output.h"
|
#include "pwm_output.h"
|
||||||
|
#include "system.h"
|
||||||
|
|
||||||
#define MULTISHOT_5US_PW (MULTISHOT_TIMER_MHZ * 5)
|
#define MULTISHOT_5US_PW (MULTISHOT_TIMER_MHZ * 5)
|
||||||
#define MULTISHOT_20US_MULT (MULTISHOT_TIMER_MHZ * 20 / 1000.0f)
|
#define MULTISHOT_20US_MULT (MULTISHOT_TIMER_MHZ * 20 / 1000.0f)
|
||||||
|
@ -280,3 +281,28 @@ void servoInit(const servoConfig_t *servoConfig)
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#ifdef BRUSHED_ESC_AUTODETECT
|
||||||
|
uint8_t hardwareMotorType = MOTOR_UNKNOWN;
|
||||||
|
|
||||||
|
void detectBrushedESC(void)
|
||||||
|
{
|
||||||
|
int i = 0;
|
||||||
|
while (!(timerHardware[i].usageFlags & TIM_USE_MOTOR) && (i < USABLE_TIMER_CHANNEL_COUNT)) {
|
||||||
|
i++;
|
||||||
|
}
|
||||||
|
|
||||||
|
IO_t MotorDetectPin = IOGetByTag(timerHardware[i].tag);
|
||||||
|
IOInit(MotorDetectPin, OWNER_SYSTEM, 0);
|
||||||
|
IOConfigGPIO(MotorDetectPin, IOCFG_IPU);
|
||||||
|
|
||||||
|
delayMicroseconds(10); // allow configuration to settle
|
||||||
|
|
||||||
|
// Check presence of brushed ESC's
|
||||||
|
if (IORead(MotorDetectPin)) {
|
||||||
|
hardwareMotorType = MOTOR_BRUSHLESS;
|
||||||
|
} else {
|
||||||
|
hardwareMotorType = MOTOR_BRUSHED;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
|
@ -114,3 +114,15 @@ pwmOutputPort_t *pwmGetMotors(void);
|
||||||
bool pwmIsSynced(void);
|
bool pwmIsSynced(void);
|
||||||
void pwmDisableMotors(void);
|
void pwmDisableMotors(void);
|
||||||
void pwmEnableMotors(void);
|
void pwmEnableMotors(void);
|
||||||
|
|
||||||
|
#ifdef BRUSHED_ESC_AUTODETECT
|
||||||
|
typedef enum {
|
||||||
|
MOTOR_UNKNOWN = 0,
|
||||||
|
MOTOR_BRUSHED,
|
||||||
|
MOTOR_BRUSHLESS
|
||||||
|
} HardwareMotorTypes_e;
|
||||||
|
|
||||||
|
extern uint8_t hardwareMotorType;
|
||||||
|
|
||||||
|
void detectBrushedESC(void);
|
||||||
|
#endif
|
||||||
|
|
|
@ -179,8 +179,11 @@ serialPort_t *uartOpen(USART_TypeDef *USARTx, serialReceiveCallbackPtr callback,
|
||||||
{
|
{
|
||||||
uartPort_t *s = NULL;
|
uartPort_t *s = NULL;
|
||||||
|
|
||||||
if (USARTx == USART1) {
|
if (false) {
|
||||||
|
#ifdef USE_UART1
|
||||||
|
} else if (USARTx == USART1) {
|
||||||
s = serialUART1(baudRate, mode, options);
|
s = serialUART1(baudRate, mode, options);
|
||||||
|
#endif
|
||||||
#ifdef USE_UART2
|
#ifdef USE_UART2
|
||||||
} else if (USARTx == USART2) {
|
} else if (USARTx == USART2) {
|
||||||
s = serialUART2(baudRate, mode, options);
|
s = serialUART2(baudRate, mode, options);
|
||||||
|
|
|
@ -872,7 +872,7 @@ const timerHardware_t *timerGetByTag(ioTag_t tag, timerUsageFlag_e flag)
|
||||||
{
|
{
|
||||||
for (int i = 0; i < USABLE_TIMER_CHANNEL_COUNT; i++) {
|
for (int i = 0; i < USABLE_TIMER_CHANNEL_COUNT; i++) {
|
||||||
if (timerHardware[i].tag == tag) {
|
if (timerHardware[i].tag == tag) {
|
||||||
if (timerHardware[i].output & flag) {
|
if (timerHardware[i].usageFlags & flag || flag == 0) {
|
||||||
return &timerHardware[i];
|
return &timerHardware[i];
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
|
@ -274,9 +274,19 @@ void resetMotorConfig(motorConfig_t *motorConfig)
|
||||||
motorConfig->motorPwmProtocol = PWM_TYPE_BRUSHED;
|
motorConfig->motorPwmProtocol = PWM_TYPE_BRUSHED;
|
||||||
motorConfig->useUnsyncedPwm = true;
|
motorConfig->useUnsyncedPwm = true;
|
||||||
#else
|
#else
|
||||||
|
#ifdef BRUSHED_ESC_AUTODETECT
|
||||||
|
if (hardwareMotorType == MOTOR_BRUSHED) {
|
||||||
|
motorConfig->minthrottle = 1000;
|
||||||
|
motorConfig->motorPwmRate = BRUSHED_MOTORS_PWM_RATE;
|
||||||
|
motorConfig->motorPwmProtocol = PWM_TYPE_BRUSHED;
|
||||||
|
motorConfig->useUnsyncedPwm = true;
|
||||||
|
} else
|
||||||
|
#endif
|
||||||
|
{
|
||||||
motorConfig->minthrottle = 1070;
|
motorConfig->minthrottle = 1070;
|
||||||
motorConfig->motorPwmRate = BRUSHLESS_MOTORS_PWM_RATE;
|
motorConfig->motorPwmRate = BRUSHLESS_MOTORS_PWM_RATE;
|
||||||
motorConfig->motorPwmProtocol = PWM_TYPE_ONESHOT125;
|
motorConfig->motorPwmProtocol = PWM_TYPE_ONESHOT125;
|
||||||
|
}
|
||||||
#endif
|
#endif
|
||||||
motorConfig->maxthrottle = 2000;
|
motorConfig->maxthrottle = 2000;
|
||||||
motorConfig->mincommand = 1000;
|
motorConfig->mincommand = 1000;
|
||||||
|
@ -490,6 +500,46 @@ void resetMax7456Config(vcdProfile_t *pVcdProfile)
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
void resetStatusLedConfig(statusLedConfig_t *statusLedConfig)
|
||||||
|
{
|
||||||
|
for (int i = 0; i < LED_NUMBER; i++) {
|
||||||
|
statusLedConfig->ledTags[i] = IO_TAG_NONE;
|
||||||
|
}
|
||||||
|
|
||||||
|
#ifdef LED0
|
||||||
|
statusLedConfig->ledTags[0] = IO_TAG(LED0);
|
||||||
|
#endif
|
||||||
|
#ifdef LED1
|
||||||
|
statusLedConfig->ledTags[1] = IO_TAG(LED1);
|
||||||
|
#endif
|
||||||
|
#ifdef LED2
|
||||||
|
statusLedConfig->ledTags[2] = IO_TAG(LED2);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
statusLedConfig->polarity = 0
|
||||||
|
#ifdef LED0_INVERTED
|
||||||
|
| BIT(0)
|
||||||
|
#endif
|
||||||
|
#ifdef LED1_INVERTED
|
||||||
|
| BIT(1)
|
||||||
|
#endif
|
||||||
|
#ifdef LED2_INVERTED
|
||||||
|
| BIT(2)
|
||||||
|
#endif
|
||||||
|
;
|
||||||
|
}
|
||||||
|
|
||||||
|
#ifdef USE_FLASHFS
|
||||||
|
void resetFlashConfig(flashConfig_t *flashConfig)
|
||||||
|
{
|
||||||
|
#ifdef M25P16_CS_PIN
|
||||||
|
flashConfig->csTag = IO_TAG(M25P16_CS_PIN);
|
||||||
|
#else
|
||||||
|
flashConfig->csTag = IO_TAG_NONE;
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
uint8_t getCurrentProfile(void)
|
uint8_t getCurrentProfile(void)
|
||||||
{
|
{
|
||||||
return masterConfig.current_profile_index;
|
return masterConfig.current_profile_index;
|
||||||
|
@ -789,6 +839,12 @@ void createDefaultConfig(master_t *config)
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#ifdef USE_FLASHFS
|
||||||
|
resetFlashConfig(&config->flashConfig);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
resetStatusLedConfig(&config->statusLedConfig);
|
||||||
|
|
||||||
#if defined(TARGET_CONFIG)
|
#if defined(TARGET_CONFIG)
|
||||||
targetConfiguration(config);
|
targetConfiguration(config);
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -55,7 +55,7 @@ typedef enum {
|
||||||
FEATURE_VTX = 1 << 24,
|
FEATURE_VTX = 1 << 24,
|
||||||
FEATURE_RX_SPI = 1 << 25,
|
FEATURE_RX_SPI = 1 << 25,
|
||||||
FEATURE_SOFTSPI = 1 << 26,
|
FEATURE_SOFTSPI = 1 << 26,
|
||||||
FEATURE_ESC_TELEMETRY = 1 << 27
|
FEATURE_ESC_SENSOR = 1 << 27,
|
||||||
} features_e;
|
} features_e;
|
||||||
|
|
||||||
void beeperOffSet(uint32_t mask);
|
void beeperOffSet(uint32_t mask);
|
||||||
|
|
|
@ -882,6 +882,7 @@ static bool mspFcProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst, mspPostProcessFn
|
||||||
sbufWriteU8(dst, batteryConfig()->vbatmincellvoltage);
|
sbufWriteU8(dst, batteryConfig()->vbatmincellvoltage);
|
||||||
sbufWriteU8(dst, batteryConfig()->vbatmaxcellvoltage);
|
sbufWriteU8(dst, batteryConfig()->vbatmaxcellvoltage);
|
||||||
sbufWriteU8(dst, batteryConfig()->vbatwarningcellvoltage);
|
sbufWriteU8(dst, batteryConfig()->vbatwarningcellvoltage);
|
||||||
|
sbufWriteU8(dst, batteryConfig()->batteryMeterType);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case MSP_CURRENT_METER_CONFIG:
|
case MSP_CURRENT_METER_CONFIG:
|
||||||
|
@ -1662,6 +1663,9 @@ static mspResult_e mspFcProcessInCommand(uint8_t cmdMSP, sbuf_t *src)
|
||||||
batteryConfig()->vbatmincellvoltage = sbufReadU8(src); // vbatlevel_warn1 in MWC2.3 GUI
|
batteryConfig()->vbatmincellvoltage = sbufReadU8(src); // vbatlevel_warn1 in MWC2.3 GUI
|
||||||
batteryConfig()->vbatmaxcellvoltage = sbufReadU8(src); // vbatlevel_warn2 in MWC2.3 GUI
|
batteryConfig()->vbatmaxcellvoltage = sbufReadU8(src); // vbatlevel_warn2 in MWC2.3 GUI
|
||||||
batteryConfig()->vbatwarningcellvoltage = sbufReadU8(src); // vbatlevel when buzzer starts to alert
|
batteryConfig()->vbatwarningcellvoltage = sbufReadU8(src); // vbatlevel when buzzer starts to alert
|
||||||
|
if (dataSize > 4) {
|
||||||
|
batteryConfig()->batteryMeterType = sbufReadU8(src);
|
||||||
|
}
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case MSP_SET_CURRENT_METER_CONFIG:
|
case MSP_SET_CURRENT_METER_CONFIG:
|
||||||
|
|
|
@ -22,7 +22,6 @@
|
||||||
#include <platform.h>
|
#include <platform.h>
|
||||||
|
|
||||||
#include "cms/cms.h"
|
#include "cms/cms.h"
|
||||||
#include "cms/cms_types.h"
|
|
||||||
|
|
||||||
#include "common/axis.h"
|
#include "common/axis.h"
|
||||||
#include "common/color.h"
|
#include "common/color.h"
|
||||||
|
@ -65,11 +64,11 @@
|
||||||
#include "sensors/compass.h"
|
#include "sensors/compass.h"
|
||||||
#include "sensors/gyro.h"
|
#include "sensors/gyro.h"
|
||||||
#include "sensors/sonar.h"
|
#include "sensors/sonar.h"
|
||||||
|
#include "sensors/esc_sensor.h"
|
||||||
|
|
||||||
#include "scheduler/scheduler.h"
|
#include "scheduler/scheduler.h"
|
||||||
|
|
||||||
#include "telemetry/telemetry.h"
|
#include "telemetry/telemetry.h"
|
||||||
#include "telemetry/esc_telemetry.h"
|
|
||||||
|
|
||||||
#include "config/feature.h"
|
#include "config/feature.h"
|
||||||
#include "config/config_profile.h"
|
#include "config/config_profile.h"
|
||||||
|
@ -111,9 +110,9 @@ static void taskHandleSerial(timeUs_t currentTimeUs)
|
||||||
|
|
||||||
static void taskUpdateBattery(timeUs_t currentTimeUs)
|
static void taskUpdateBattery(timeUs_t currentTimeUs)
|
||||||
{
|
{
|
||||||
#ifdef USE_ADC
|
#if defined(USE_ADC) || defined(USE_ESC_SENSOR)
|
||||||
static uint32_t vbatLastServiced = 0;
|
static uint32_t vbatLastServiced = 0;
|
||||||
if (feature(FEATURE_VBAT) || feature(FEATURE_ESC_TELEMETRY)) {
|
if (feature(FEATURE_VBAT) || feature(FEATURE_ESC_SENSOR)) {
|
||||||
if (cmp32(currentTimeUs, vbatLastServiced) >= VBATINTERVAL) {
|
if (cmp32(currentTimeUs, vbatLastServiced) >= VBATINTERVAL) {
|
||||||
vbatLastServiced = currentTimeUs;
|
vbatLastServiced = currentTimeUs;
|
||||||
updateBattery();
|
updateBattery();
|
||||||
|
@ -122,7 +121,7 @@ static void taskUpdateBattery(timeUs_t currentTimeUs)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
static uint32_t ibatLastServiced = 0;
|
static uint32_t ibatLastServiced = 0;
|
||||||
if (feature(FEATURE_CURRENT_METER) || feature(FEATURE_ESC_TELEMETRY)) {
|
if (feature(FEATURE_CURRENT_METER) || feature(FEATURE_ESC_SENSOR)) {
|
||||||
const int32_t ibatTimeSinceLastServiced = cmp32(currentTimeUs, ibatLastServiced);
|
const int32_t ibatTimeSinceLastServiced = cmp32(currentTimeUs, ibatLastServiced);
|
||||||
|
|
||||||
if (ibatTimeSinceLastServiced >= IBATINTERVAL) {
|
if (ibatTimeSinceLastServiced >= IBATINTERVAL) {
|
||||||
|
@ -205,15 +204,6 @@ static void taskTelemetry(timeUs_t currentTimeUs)
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef USE_ESC_TELEMETRY
|
|
||||||
static void taskEscTelemetry(timeUs_t currentTimeUs)
|
|
||||||
{
|
|
||||||
if (feature(FEATURE_ESC_TELEMETRY)) {
|
|
||||||
escTelemetryProcess(currentTimeUs);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifdef VTX_CONTROL
|
#ifdef VTX_CONTROL
|
||||||
// Everything that listens to VTX devices
|
// Everything that listens to VTX devices
|
||||||
void taskVtxControl(uint32_t currentTime)
|
void taskVtxControl(uint32_t currentTime)
|
||||||
|
@ -292,8 +282,8 @@ void fcTasksInit(void)
|
||||||
#ifdef USE_BST
|
#ifdef USE_BST
|
||||||
setTaskEnabled(TASK_BST_MASTER_PROCESS, true);
|
setTaskEnabled(TASK_BST_MASTER_PROCESS, true);
|
||||||
#endif
|
#endif
|
||||||
#ifdef USE_ESC_TELEMETRY
|
#ifdef USE_ESC_SENSOR
|
||||||
setTaskEnabled(TASK_ESC_TELEMETRY, feature(FEATURE_ESC_TELEMETRY));
|
setTaskEnabled(TASK_ESC_SENSOR, feature(FEATURE_ESC_SENSOR));
|
||||||
#endif
|
#endif
|
||||||
#ifdef CMS
|
#ifdef CMS
|
||||||
#ifdef USE_MSP_DISPLAYPORT
|
#ifdef USE_MSP_DISPLAYPORT
|
||||||
|
@ -470,11 +460,11 @@ cfTask_t cfTasks[TASK_COUNT] = {
|
||||||
},
|
},
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef USE_ESC_TELEMETRY
|
#ifdef USE_ESC_SENSOR
|
||||||
[TASK_ESC_TELEMETRY] = {
|
[TASK_ESC_SENSOR] = {
|
||||||
.taskName = "ESC_TELEMETRY",
|
.taskName = "ESC_SENSOR",
|
||||||
.taskFunc = taskEscTelemetry,
|
.taskFunc = escSensorProcess,
|
||||||
.desiredPeriod = 1000000 / 100, // 100 Hz
|
.desiredPeriod = TASK_PERIOD_HZ(100), // 100 Hz every 10ms
|
||||||
.staticPriority = TASK_PRIORITY_LOW,
|
.staticPriority = TASK_PRIORITY_LOW,
|
||||||
},
|
},
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -37,7 +37,7 @@ typedef enum {
|
||||||
FUNCTION_BLACKBOX = (1 << 7), // 128
|
FUNCTION_BLACKBOX = (1 << 7), // 128
|
||||||
|
|
||||||
FUNCTION_TELEMETRY_MAVLINK = (1 << 9), // 512
|
FUNCTION_TELEMETRY_MAVLINK = (1 << 9), // 512
|
||||||
FUNCTION_TELEMETRY_ESC = (1 << 10), // 1024
|
FUNCTION_ESC_SENSOR = (1 << 10),// 1024
|
||||||
FUNCTION_VTX_CONTROL = (1 << 11),// 2048
|
FUNCTION_VTX_CONTROL = (1 << 11),// 2048
|
||||||
} serialPortFunction_e;
|
} serialPortFunction_e;
|
||||||
|
|
||||||
|
|
|
@ -234,7 +234,7 @@ static const char * const featureNames[] = {
|
||||||
"SONAR", "TELEMETRY", "CURRENT_METER", "3D", "RX_PARALLEL_PWM",
|
"SONAR", "TELEMETRY", "CURRENT_METER", "3D", "RX_PARALLEL_PWM",
|
||||||
"RX_MSP", "RSSI_ADC", "LED_STRIP", "DISPLAY", "OSD",
|
"RX_MSP", "RSSI_ADC", "LED_STRIP", "DISPLAY", "OSD",
|
||||||
"BLACKBOX", "CHANNEL_FORWARDING", "TRANSPONDER", "AIRMODE",
|
"BLACKBOX", "CHANNEL_FORWARDING", "TRANSPONDER", "AIRMODE",
|
||||||
"SDCARD", "VTX", "RX_SPI", "SOFTSPI", "ESC_TELEMETRY", NULL
|
"SDCARD", "VTX", "RX_SPI", "SOFTSPI", "ESC_SENSOR", NULL
|
||||||
};
|
};
|
||||||
|
|
||||||
// sync this with rxFailsafeChannelMode_e
|
// sync this with rxFailsafeChannelMode_e
|
||||||
|
@ -415,7 +415,11 @@ static const char * const lookupTableGPSSBASMode[] = {
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
static const char * const lookupTableCurrentSensor[] = {
|
static const char * const lookupTableCurrentSensor[] = {
|
||||||
"NONE", "ADC", "VIRTUAL"
|
"NONE", "ADC", "VIRTUAL", "ESC"
|
||||||
|
};
|
||||||
|
|
||||||
|
static const char * const lookupTableBatterySensor[] = {
|
||||||
|
"ADC", "ESC"
|
||||||
};
|
};
|
||||||
|
|
||||||
#ifdef USE_SERVOS
|
#ifdef USE_SERVOS
|
||||||
|
@ -519,7 +523,7 @@ static const char * const lookupTableDebug[DEBUG_COUNT] = {
|
||||||
"VELOCITY",
|
"VELOCITY",
|
||||||
"DFILTER",
|
"DFILTER",
|
||||||
"ANGLERATE",
|
"ANGLERATE",
|
||||||
"ESC_TELEMETRY",
|
"ESC_SENSOR",
|
||||||
"SCHEDULER",
|
"SCHEDULER",
|
||||||
};
|
};
|
||||||
|
|
||||||
|
@ -571,6 +575,7 @@ typedef enum {
|
||||||
TABLE_BLACKBOX_DEVICE,
|
TABLE_BLACKBOX_DEVICE,
|
||||||
#endif
|
#endif
|
||||||
TABLE_CURRENT_SENSOR,
|
TABLE_CURRENT_SENSOR,
|
||||||
|
TABLE_BATTERY_SENSOR,
|
||||||
#ifdef USE_SERVOS
|
#ifdef USE_SERVOS
|
||||||
TABLE_GIMBAL_MODE,
|
TABLE_GIMBAL_MODE,
|
||||||
#endif
|
#endif
|
||||||
|
@ -611,6 +616,7 @@ static const lookupTableEntry_t lookupTables[] = {
|
||||||
{ lookupTableBlackboxDevice, sizeof(lookupTableBlackboxDevice) / sizeof(char *) },
|
{ lookupTableBlackboxDevice, sizeof(lookupTableBlackboxDevice) / sizeof(char *) },
|
||||||
#endif
|
#endif
|
||||||
{ lookupTableCurrentSensor, sizeof(lookupTableCurrentSensor) / sizeof(char *) },
|
{ lookupTableCurrentSensor, sizeof(lookupTableCurrentSensor) / sizeof(char *) },
|
||||||
|
{ lookupTableBatterySensor, sizeof(lookupTableBatterySensor) / sizeof(char *) },
|
||||||
#ifdef USE_SERVOS
|
#ifdef USE_SERVOS
|
||||||
{ lookupTableGimbalMode, sizeof(lookupTableGimbalMode) / sizeof(char *) },
|
{ lookupTableGimbalMode, sizeof(lookupTableGimbalMode) / sizeof(char *) },
|
||||||
#endif
|
#endif
|
||||||
|
@ -799,6 +805,7 @@ const clivalue_t valueTable[] = {
|
||||||
{ "current_meter_offset", VAR_INT16 | MASTER_VALUE, &batteryConfig()->currentMeterOffset, .config.minmax = { -16000, 16000 } },
|
{ "current_meter_offset", VAR_INT16 | MASTER_VALUE, &batteryConfig()->currentMeterOffset, .config.minmax = { -16000, 16000 } },
|
||||||
{ "multiwii_current_meter_output", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &batteryConfig()->multiwiiCurrentMeterOutput, .config.lookup = { TABLE_OFF_ON } },
|
{ "multiwii_current_meter_output", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &batteryConfig()->multiwiiCurrentMeterOutput, .config.lookup = { TABLE_OFF_ON } },
|
||||||
{ "current_meter_type", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &batteryConfig()->currentMeterType, .config.lookup = { TABLE_CURRENT_SENSOR } },
|
{ "current_meter_type", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &batteryConfig()->currentMeterType, .config.lookup = { TABLE_CURRENT_SENSOR } },
|
||||||
|
{ "battery_meter_type", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &batteryConfig()->batteryMeterType, .config.lookup = { TABLE_BATTERY_SENSOR } },
|
||||||
{ "battery_notpresent_level", VAR_UINT8 | MASTER_VALUE, &batteryConfig()->batterynotpresentlevel, .config.minmax = { 0, 200 } },
|
{ "battery_notpresent_level", VAR_UINT8 | MASTER_VALUE, &batteryConfig()->batterynotpresentlevel, .config.minmax = { 0, 200 } },
|
||||||
{ "use_vbat_alerts", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &batteryConfig()->useVBatAlerts, .config.lookup = { TABLE_OFF_ON } },
|
{ "use_vbat_alerts", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &batteryConfig()->useVBatAlerts, .config.lookup = { TABLE_OFF_ON } },
|
||||||
{ "use_consumption_alerts", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &batteryConfig()->useConsumptionAlerts, .config.lookup = { TABLE_OFF_ON } },
|
{ "use_consumption_alerts", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &batteryConfig()->useConsumptionAlerts, .config.lookup = { TABLE_OFF_ON } },
|
||||||
|
|
123
src/main/main.c
123
src/main/main.c
|
@ -36,7 +36,6 @@
|
||||||
#include "drivers/sensor.h"
|
#include "drivers/sensor.h"
|
||||||
#include "drivers/system.h"
|
#include "drivers/system.h"
|
||||||
#include "drivers/dma.h"
|
#include "drivers/dma.h"
|
||||||
#include "drivers/gpio.h"
|
|
||||||
#include "drivers/io.h"
|
#include "drivers/io.h"
|
||||||
#include "drivers/light_led.h"
|
#include "drivers/light_led.h"
|
||||||
#include "drivers/sound_beeper.h"
|
#include "drivers/sound_beeper.h"
|
||||||
|
@ -106,7 +105,7 @@
|
||||||
#include "sensors/initialisation.h"
|
#include "sensors/initialisation.h"
|
||||||
|
|
||||||
#include "telemetry/telemetry.h"
|
#include "telemetry/telemetry.h"
|
||||||
#include "telemetry/esc_telemetry.h"
|
#include "sensors/esc_sensor.h"
|
||||||
|
|
||||||
#include "flight/pid.h"
|
#include "flight/pid.h"
|
||||||
#include "flight/imu.h"
|
#include "flight/imu.h"
|
||||||
|
@ -126,6 +125,10 @@
|
||||||
#include "build/build_config.h"
|
#include "build/build_config.h"
|
||||||
#include "build/debug.h"
|
#include "build/debug.h"
|
||||||
|
|
||||||
|
#ifdef TARGET_BUS_INIT
|
||||||
|
void targetBusInit(void);
|
||||||
|
#endif
|
||||||
|
|
||||||
extern uint8_t motorControlEnable;
|
extern uint8_t motorControlEnable;
|
||||||
|
|
||||||
#ifdef SOFTSERIAL_LOOPBACK
|
#ifdef SOFTSERIAL_LOOPBACK
|
||||||
|
@ -160,6 +163,10 @@ void init(void)
|
||||||
detectHardwareRevision();
|
detectHardwareRevision();
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#ifdef BRUSHED_ESC_AUTODETECT
|
||||||
|
detectBrushedESC();
|
||||||
|
#endif
|
||||||
|
|
||||||
initEEPROM();
|
initEEPROM();
|
||||||
|
|
||||||
ensureEEPROMContainsValidData();
|
ensureEEPROMContainsValidData();
|
||||||
|
@ -174,11 +181,7 @@ void init(void)
|
||||||
// Latch active features to be used for feature() in the remainder of init().
|
// Latch active features to be used for feature() in the remainder of init().
|
||||||
latchActiveFeatures();
|
latchActiveFeatures();
|
||||||
|
|
||||||
#ifdef ALIENFLIGHTF3
|
ledInit(&masterConfig.statusLedConfig);
|
||||||
ledInit(hardwareRevision == AFF3_REV_1 ? false : true);
|
|
||||||
#else
|
|
||||||
ledInit(false);
|
|
||||||
#endif
|
|
||||||
LED2_ON;
|
LED2_ON;
|
||||||
|
|
||||||
#ifdef USE_EXTI
|
#ifdef USE_EXTI
|
||||||
|
@ -186,28 +189,22 @@ void init(void)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if defined(BUTTONS)
|
#if defined(BUTTONS)
|
||||||
gpio_config_t buttonAGpioConfig = {
|
IO_t buttonAPin = IOGetByTag(IO_TAG(BUTTON_A_PIN));
|
||||||
BUTTON_A_PIN,
|
IOInit(buttonAPin, OWNER_SYSTEM, 0);
|
||||||
Mode_IPU,
|
IOConfigGPIO(buttonAPin, IOCFG_IPU);
|
||||||
Speed_2MHz
|
|
||||||
};
|
|
||||||
gpioInit(BUTTON_A_PORT, &buttonAGpioConfig);
|
|
||||||
|
|
||||||
gpio_config_t buttonBGpioConfig = {
|
IO_t buttonBPin = IOGetByTag(IO_TAG(BUTTON_B_PIN));
|
||||||
BUTTON_B_PIN,
|
IOInit(buttonBPin, OWNER_SYSTEM, 0);
|
||||||
Mode_IPU,
|
IOConfigGPIO(buttonBPin, IOCFG_IPU);
|
||||||
Speed_2MHz
|
|
||||||
};
|
|
||||||
gpioInit(BUTTON_B_PORT, &buttonBGpioConfig);
|
|
||||||
|
|
||||||
// Check status of bind plug and exit if not active
|
// Check status of bind plug and exit if not active
|
||||||
delayMicroseconds(10); // allow GPIO configuration to settle
|
delayMicroseconds(10); // allow configuration to settle
|
||||||
|
|
||||||
if (!isMPUSoftReset()) {
|
if (!isMPUSoftReset()) {
|
||||||
uint8_t secondsRemaining = 5;
|
uint8_t secondsRemaining = 5;
|
||||||
bool bothButtonsHeld;
|
bool bothButtonsHeld;
|
||||||
do {
|
do {
|
||||||
bothButtonsHeld = !digitalIn(BUTTON_A_PORT, BUTTON_A_PIN) && !digitalIn(BUTTON_B_PORT, BUTTON_B_PIN);
|
bothButtonsHeld = !IORead(buttonAPin) && !IORead(buttonBPin);
|
||||||
if (bothButtonsHeld) {
|
if (bothButtonsHeld) {
|
||||||
if (--secondsRemaining == 0) {
|
if (--secondsRemaining == 0) {
|
||||||
resetEEPROM();
|
resetEEPROM();
|
||||||
|
@ -293,7 +290,6 @@ void init(void)
|
||||||
pwmRxSetInputFilteringMode(masterConfig.inputFilteringMode);
|
pwmRxSetInputFilteringMode(masterConfig.inputFilteringMode);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
||||||
systemState |= SYSTEM_STATE_MOTORS_READY;
|
systemState |= SYSTEM_STATE_MOTORS_READY;
|
||||||
|
|
||||||
#ifdef BEEPER
|
#ifdef BEEPER
|
||||||
|
@ -308,74 +304,48 @@ void init(void)
|
||||||
bstInit(BST_DEVICE);
|
bstInit(BST_DEVICE);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef USE_SPI
|
#ifdef TARGET_BUS_INIT
|
||||||
#ifdef USE_SPI_DEVICE_1
|
targetBusInit();
|
||||||
spiInit(SPIDEV_1);
|
|
||||||
#endif
|
|
||||||
#ifdef USE_SPI_DEVICE_2
|
|
||||||
spiInit(SPIDEV_2);
|
|
||||||
#endif
|
|
||||||
#ifdef USE_SPI_DEVICE_3
|
|
||||||
#ifdef ALIENFLIGHTF3
|
|
||||||
if (hardwareRevision == AFF3_REV_2) {
|
|
||||||
spiInit(SPIDEV_3);
|
|
||||||
}
|
|
||||||
#else
|
#else
|
||||||
|
#ifdef USE_SPI
|
||||||
|
#ifdef USE_SPI_DEVICE_1
|
||||||
|
spiInit(SPIDEV_1);
|
||||||
|
#endif
|
||||||
|
#ifdef USE_SPI_DEVICE_2
|
||||||
|
spiInit(SPIDEV_2);
|
||||||
|
#endif
|
||||||
|
#ifdef USE_SPI_DEVICE_3
|
||||||
spiInit(SPIDEV_3);
|
spiInit(SPIDEV_3);
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#ifdef USE_SPI_DEVICE_4
|
||||||
#ifdef USE_SPI_DEVICE_4
|
|
||||||
spiInit(SPIDEV_4);
|
spiInit(SPIDEV_4);
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef VTX
|
#ifdef USE_I2C
|
||||||
vtxInit();
|
i2cInit(I2C_DEVICE);
|
||||||
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef USE_HARDWARE_REVISION_DETECTION
|
#ifdef USE_HARDWARE_REVISION_DETECTION
|
||||||
updateHardwareRevision();
|
updateHardwareRevision();
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if defined(NAZE)
|
#ifdef VTX
|
||||||
if (hardwareRevision == NAZE32_SP) {
|
vtxInit();
|
||||||
serialRemovePort(SERIAL_PORT_SOFTSERIAL2);
|
|
||||||
} else {
|
|
||||||
serialRemovePort(SERIAL_PORT_USART3);
|
|
||||||
}
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if defined(SPRACINGF3) && defined(SONAR) && defined(USE_SOFTSERIAL2)
|
#if defined(SONAR_SOFTSERIAL2_EXCLUSIVE) && defined(SONAR) && defined(USE_SOFTSERIAL2)
|
||||||
if (feature(FEATURE_SONAR) && feature(FEATURE_SOFTSERIAL)) {
|
if (feature(FEATURE_SONAR) && feature(FEATURE_SOFTSERIAL)) {
|
||||||
serialRemovePort(SERIAL_PORT_SOFTSERIAL2);
|
serialRemovePort(SERIAL_PORT_SOFTSERIAL2);
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if defined(SPRACINGF3MINI) || defined(OMNIBUS) || defined(X_RACERSPI)
|
#if defined(SONAR_SOFTSERIAL1_EXCLUSIVE) && defined(SONAR) && defined(USE_SOFTSERIAL1)
|
||||||
#if defined(SONAR) && defined(USE_SOFTSERIAL1)
|
|
||||||
if (feature(FEATURE_SONAR) && feature(FEATURE_SOFTSERIAL)) {
|
if (feature(FEATURE_SONAR) && feature(FEATURE_SOFTSERIAL)) {
|
||||||
serialRemovePort(SERIAL_PORT_SOFTSERIAL1);
|
serialRemovePort(SERIAL_PORT_SOFTSERIAL1);
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifdef USE_I2C
|
|
||||||
#if defined(NAZE)
|
|
||||||
if (hardwareRevision != NAZE32_SP) {
|
|
||||||
i2cInit(I2C_DEVICE);
|
|
||||||
} else {
|
|
||||||
if (!doesConfigurationUsePort(SERIAL_PORT_USART3)) {
|
|
||||||
i2cInit(I2C_DEVICE);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
#elif defined(CC3D)
|
|
||||||
if (!doesConfigurationUsePort(SERIAL_PORT_USART3)) {
|
|
||||||
i2cInit(I2C_DEVICE);
|
|
||||||
}
|
|
||||||
#else
|
|
||||||
i2cInit(I2C_DEVICE);
|
|
||||||
#endif
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifdef USE_ADC
|
#ifdef USE_ADC
|
||||||
/* these can be removed from features! */
|
/* these can be removed from features! */
|
||||||
|
@ -385,7 +355,6 @@ void init(void)
|
||||||
adcInit(&masterConfig.adcConfig);
|
adcInit(&masterConfig.adcConfig);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
||||||
initBoardAlignment(&masterConfig.boardAlignment);
|
initBoardAlignment(&masterConfig.boardAlignment);
|
||||||
|
|
||||||
#ifdef CMS
|
#ifdef CMS
|
||||||
|
@ -495,9 +464,9 @@ void init(void)
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef USE_ESC_TELEMETRY
|
#ifdef USE_ESC_SENSOR
|
||||||
if (feature(FEATURE_ESC_TELEMETRY)) {
|
if (feature(FEATURE_ESC_SENSOR)) {
|
||||||
escTelemetryInit();
|
escSensorInit();
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
@ -515,12 +484,8 @@ void init(void)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef USE_FLASHFS
|
#ifdef USE_FLASHFS
|
||||||
#ifdef NAZE
|
#if defined(USE_FLASH_M25P16)
|
||||||
if (hardwareRevision == NAZE32_REV5) {
|
m25p16_init(&masterConfig.flashConfig);
|
||||||
m25p16_init(IO_TAG_NONE);
|
|
||||||
}
|
|
||||||
#elif defined(USE_FLASH_M25P16)
|
|
||||||
m25p16_init(IO_TAG_NONE);
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
flashfsInit();
|
flashfsInit();
|
||||||
|
|
|
@ -59,7 +59,7 @@
|
||||||
#define MSP_PROTOCOL_VERSION 0
|
#define MSP_PROTOCOL_VERSION 0
|
||||||
|
|
||||||
#define API_VERSION_MAJOR 1 // increment when major changes are made
|
#define API_VERSION_MAJOR 1 // increment when major changes are made
|
||||||
#define API_VERSION_MINOR 22 // increment when any change is made, reset to zero when major changes are released after changing API_VERSION_MAJOR
|
#define API_VERSION_MINOR 23 // increment when any change is made, reset to zero when major changes are released after changing API_VERSION_MAJOR
|
||||||
|
|
||||||
#define API_VERSION_LENGTH 2
|
#define API_VERSION_LENGTH 2
|
||||||
|
|
||||||
|
|
|
@ -17,7 +17,7 @@
|
||||||
|
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
#if defined(STM32F745xx)
|
#if defined(STM32F745xx) || defined(STM32F746xx)
|
||||||
#include "stm32f7xx.h"
|
#include "stm32f7xx.h"
|
||||||
#include "stm32f7xx_hal.h"
|
#include "stm32f7xx_hal.h"
|
||||||
|
|
||||||
|
|
|
@ -94,8 +94,8 @@ typedef enum {
|
||||||
#ifdef USE_BST
|
#ifdef USE_BST
|
||||||
TASK_BST_MASTER_PROCESS,
|
TASK_BST_MASTER_PROCESS,
|
||||||
#endif
|
#endif
|
||||||
#ifdef USE_ESC_TELEMETRY
|
#ifdef USE_ESC_SENSOR
|
||||||
TASK_ESC_TELEMETRY,
|
TASK_ESC_SENSOR,
|
||||||
#endif
|
#endif
|
||||||
#ifdef CMS
|
#ifdef CMS
|
||||||
TASK_CMS,
|
TASK_CMS,
|
||||||
|
|
|
@ -34,8 +34,7 @@
|
||||||
#include "config/feature.h"
|
#include "config/feature.h"
|
||||||
|
|
||||||
#include "sensors/battery.h"
|
#include "sensors/battery.h"
|
||||||
|
#include "sensors/esc_sensor.h"
|
||||||
#include "telemetry/esc_telemetry.h"
|
|
||||||
|
|
||||||
#include "fc/rc_controls.h"
|
#include "fc/rc_controls.h"
|
||||||
#include "io/beeper.h"
|
#include "io/beeper.h"
|
||||||
|
@ -84,9 +83,9 @@ static void updateBatteryVoltage(void)
|
||||||
vBatFilterIsInitialised = true;
|
vBatFilterIsInitialised = true;
|
||||||
}
|
}
|
||||||
|
|
||||||
#ifdef USE_ESC_TELEMETRY
|
#ifdef USE_ESC_SENSOR
|
||||||
if (batteryConfig->batteryMeterType == BATTERY_SENSOR_ESC && isEscTelemetryActive()) {
|
if (feature(FEATURE_ESC_SENSOR) && batteryConfig->batteryMeterType == BATTERY_SENSOR_ESC) {
|
||||||
vbatLatest = getEscTelemetryVbat();
|
vbatLatest = getEscSensorVbat();
|
||||||
if (debugMode == DEBUG_BATTERY) {
|
if (debugMode == DEBUG_BATTERY) {
|
||||||
debug[0] = -1;
|
debug[0] = -1;
|
||||||
}
|
}
|
||||||
|
@ -292,11 +291,11 @@ void updateCurrentMeter(int32_t lastUpdateAt, rxConfig_t *rxConfig, uint16_t dea
|
||||||
|
|
||||||
break;
|
break;
|
||||||
case CURRENT_SENSOR_ESC:
|
case CURRENT_SENSOR_ESC:
|
||||||
#ifdef USE_ESC_TELEMETRY
|
#ifdef USE_ESC_SENSOR
|
||||||
if (isEscTelemetryActive()) {
|
if (feature(FEATURE_ESC_SENSOR)) {
|
||||||
amperageLatest = getEscTelemetryCurrent();
|
amperageLatest = getEscSensorCurrent();
|
||||||
amperage = amperageLatest;
|
amperage = amperageLatest;
|
||||||
mAhDrawn = getEscTelemetryConsumption();
|
mAhDrawn = getEscSensorConsumption();
|
||||||
|
|
||||||
updateConsumptionWarning();
|
updateConsumptionWarning();
|
||||||
}
|
}
|
||||||
|
|
|
@ -31,12 +31,12 @@ typedef enum {
|
||||||
CURRENT_SENSOR_NONE = 0,
|
CURRENT_SENSOR_NONE = 0,
|
||||||
CURRENT_SENSOR_ADC,
|
CURRENT_SENSOR_ADC,
|
||||||
CURRENT_SENSOR_VIRTUAL,
|
CURRENT_SENSOR_VIRTUAL,
|
||||||
CURRENT_SENSOR_ESC
|
CURRENT_SENSOR_ESC,
|
||||||
|
CURRENT_SENSOR_MAX = CURRENT_SENSOR_ESC
|
||||||
} currentSensor_e;
|
} currentSensor_e;
|
||||||
|
|
||||||
typedef enum {
|
typedef enum {
|
||||||
BATTERY_SENSOR_NONE = 0,
|
BATTERY_SENSOR_ADC = 0,
|
||||||
BATTERY_SENSOR_ADC,
|
|
||||||
BATTERY_SENSOR_ESC
|
BATTERY_SENSOR_ESC
|
||||||
} batterySensor_e;
|
} batterySensor_e;
|
||||||
|
|
||||||
|
|
313
src/main/sensors/esc_sensor.c
Normal file
313
src/main/sensors/esc_sensor.c
Normal file
|
@ -0,0 +1,313 @@
|
||||||
|
#include <stdbool.h>
|
||||||
|
#include <stdint.h>
|
||||||
|
#include <stdlib.h>
|
||||||
|
|
||||||
|
#include <platform.h>
|
||||||
|
|
||||||
|
#include "fc/config.h"
|
||||||
|
#include "config/feature.h"
|
||||||
|
#include "config/config_master.h"
|
||||||
|
|
||||||
|
#include "common/utils.h"
|
||||||
|
|
||||||
|
#include "drivers/system.h"
|
||||||
|
#include "drivers/serial.h"
|
||||||
|
#include "drivers/serial_uart.h"
|
||||||
|
#include "drivers/pwm_output.h"
|
||||||
|
|
||||||
|
#include "io/serial.h"
|
||||||
|
|
||||||
|
#include "flight/mixer.h"
|
||||||
|
|
||||||
|
#include "sensors/battery.h"
|
||||||
|
|
||||||
|
#include "esc_sensor.h"
|
||||||
|
|
||||||
|
#include "build/debug.h"
|
||||||
|
|
||||||
|
/*
|
||||||
|
KISS ESC TELEMETRY PROTOCOL
|
||||||
|
---------------------------
|
||||||
|
|
||||||
|
One transmission will have 10 times 8-bit bytes sent with 115200 baud and 3.6V.
|
||||||
|
|
||||||
|
Byte 0: Temperature
|
||||||
|
Byte 1: Voltage high byte
|
||||||
|
Byte 2: Voltage low byte
|
||||||
|
Byte 3: Current high byte
|
||||||
|
Byte 4: Current low byte
|
||||||
|
Byte 5: Consumption high byte
|
||||||
|
Byte 6: Consumption low byte
|
||||||
|
Byte 7: Rpm high byte
|
||||||
|
Byte 8: Rpm low byte
|
||||||
|
Byte 9: 8-bit CRC
|
||||||
|
|
||||||
|
*/
|
||||||
|
|
||||||
|
/*
|
||||||
|
DEBUG INFORMATION
|
||||||
|
-----------------
|
||||||
|
|
||||||
|
set debug_mode = DEBUG_ESC_TELEMETRY in cli
|
||||||
|
|
||||||
|
0: current motor index requested
|
||||||
|
1: number of timeouts
|
||||||
|
2: voltage
|
||||||
|
3: current
|
||||||
|
*/
|
||||||
|
|
||||||
|
#ifdef USE_DSHOT
|
||||||
|
|
||||||
|
typedef struct {
|
||||||
|
bool skipped;
|
||||||
|
int16_t temperature;
|
||||||
|
int16_t voltage;
|
||||||
|
int16_t current;
|
||||||
|
int16_t consumption;
|
||||||
|
int16_t rpm;
|
||||||
|
} esc_telemetry_t;
|
||||||
|
|
||||||
|
typedef enum {
|
||||||
|
ESC_SENSOR_FRAME_PENDING = 1 << 0, // 1
|
||||||
|
ESC_SENSOR_FRAME_COMPLETE = 1 << 1 // 2
|
||||||
|
} escTlmFrameState_t;
|
||||||
|
|
||||||
|
typedef enum {
|
||||||
|
ESC_SENSOR_TRIGGER_WAIT = 0,
|
||||||
|
ESC_SENSOR_TRIGGER_READY = 1 << 0, // 1
|
||||||
|
ESC_SENSOR_TRIGGER_PENDING = 1 << 1, // 2
|
||||||
|
} escSensorTriggerState_t;
|
||||||
|
|
||||||
|
#define ESC_SENSOR_BAUDRATE 115200
|
||||||
|
#define ESC_SENSOR_BUFFSIZE 10
|
||||||
|
#define ESC_BOOTTIME 5000 // 5 seconds
|
||||||
|
#define ESC_REQUEST_TIMEOUT 100 // 100 ms (data transfer takes only 900us)
|
||||||
|
|
||||||
|
static bool tlmFrameDone = false;
|
||||||
|
static uint8_t tlm[ESC_SENSOR_BUFFSIZE] = { 0, };
|
||||||
|
static uint8_t tlmFramePosition = 0;
|
||||||
|
static serialPort_t *escSensorPort = NULL;
|
||||||
|
static esc_telemetry_t escSensorData[MAX_SUPPORTED_MOTORS];
|
||||||
|
static uint32_t escTriggerTimestamp = -1;
|
||||||
|
static uint32_t escLastResponseTimestamp;
|
||||||
|
static uint8_t timeoutRetryCount = 0;
|
||||||
|
static uint8_t totalRetryCount = 0;
|
||||||
|
|
||||||
|
static uint8_t escSensorMotor = 0; // motor index
|
||||||
|
static bool escSensorEnabled = false;
|
||||||
|
static escSensorTriggerState_t escSensorTriggerState = ESC_SENSOR_TRIGGER_WAIT;
|
||||||
|
|
||||||
|
static int16_t escVbat = 0;
|
||||||
|
static int16_t escCurrent = 0;
|
||||||
|
static int16_t escConsumption = 0;
|
||||||
|
|
||||||
|
static void escSensorDataReceive(uint16_t c);
|
||||||
|
static uint8_t update_crc8(uint8_t crc, uint8_t crc_seed);
|
||||||
|
static uint8_t get_crc8(uint8_t *Buf, uint8_t BufLen);
|
||||||
|
static void selectNextMotor(void);
|
||||||
|
|
||||||
|
bool isEscSensorActive(void)
|
||||||
|
{
|
||||||
|
return escSensorEnabled;
|
||||||
|
}
|
||||||
|
|
||||||
|
int16_t getEscSensorVbat(void)
|
||||||
|
{
|
||||||
|
return escVbat / 10;
|
||||||
|
}
|
||||||
|
|
||||||
|
int16_t getEscSensorCurrent(void)
|
||||||
|
{
|
||||||
|
return escCurrent;
|
||||||
|
}
|
||||||
|
|
||||||
|
int16_t getEscSensorConsumption(void)
|
||||||
|
{
|
||||||
|
return escConsumption;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool escSensorInit(void)
|
||||||
|
{
|
||||||
|
serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_ESC_SENSOR);
|
||||||
|
if (!portConfig) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
portOptions_t options = (SERIAL_NOT_INVERTED);
|
||||||
|
|
||||||
|
// Initialize serial port
|
||||||
|
escSensorPort = openSerialPort(portConfig->identifier, FUNCTION_ESC_SENSOR, escSensorDataReceive, ESC_SENSOR_BAUDRATE, MODE_RX, options);
|
||||||
|
|
||||||
|
if (escSensorPort) {
|
||||||
|
escSensorEnabled = true;
|
||||||
|
}
|
||||||
|
|
||||||
|
return escSensorPort != NULL;
|
||||||
|
}
|
||||||
|
|
||||||
|
void freeEscSensorPort(void)
|
||||||
|
{
|
||||||
|
closeSerialPort(escSensorPort);
|
||||||
|
escSensorPort = NULL;
|
||||||
|
escSensorEnabled = false;
|
||||||
|
}
|
||||||
|
|
||||||
|
// Receive ISR callback
|
||||||
|
static void escSensorDataReceive(uint16_t c)
|
||||||
|
{
|
||||||
|
// KISS ESC sends some data during startup, ignore this for now (maybe future use)
|
||||||
|
// startup data could be firmware version and serialnumber
|
||||||
|
|
||||||
|
if (escSensorTriggerState == ESC_SENSOR_TRIGGER_WAIT) return;
|
||||||
|
|
||||||
|
tlm[tlmFramePosition] = (uint8_t)c;
|
||||||
|
|
||||||
|
if (tlmFramePosition == ESC_SENSOR_BUFFSIZE - 1) {
|
||||||
|
tlmFrameDone = true;
|
||||||
|
tlmFramePosition = 0;
|
||||||
|
} else {
|
||||||
|
tlmFramePosition++;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
uint8_t escSensorFrameStatus(void)
|
||||||
|
{
|
||||||
|
uint8_t frameStatus = ESC_SENSOR_FRAME_PENDING;
|
||||||
|
uint16_t chksum, tlmsum;
|
||||||
|
|
||||||
|
if (!tlmFrameDone) {
|
||||||
|
return frameStatus;
|
||||||
|
}
|
||||||
|
|
||||||
|
tlmFrameDone = false;
|
||||||
|
|
||||||
|
// Get CRC8 checksum
|
||||||
|
chksum = get_crc8(tlm, ESC_SENSOR_BUFFSIZE - 1);
|
||||||
|
tlmsum = tlm[ESC_SENSOR_BUFFSIZE - 1]; // last byte contains CRC value
|
||||||
|
|
||||||
|
if (chksum == tlmsum) {
|
||||||
|
escSensorData[escSensorMotor].skipped = false;
|
||||||
|
escSensorData[escSensorMotor].temperature = tlm[0];
|
||||||
|
escSensorData[escSensorMotor].voltage = tlm[1] << 8 | tlm[2];
|
||||||
|
escSensorData[escSensorMotor].current = tlm[3] << 8 | tlm[4];
|
||||||
|
escSensorData[escSensorMotor].consumption = tlm[5] << 8 | tlm[6];
|
||||||
|
escSensorData[escSensorMotor].rpm = tlm[7] << 8 | tlm[8];
|
||||||
|
|
||||||
|
frameStatus = ESC_SENSOR_FRAME_COMPLETE;
|
||||||
|
}
|
||||||
|
|
||||||
|
return frameStatus;
|
||||||
|
}
|
||||||
|
|
||||||
|
void escSensorProcess(timeUs_t currentTimeUs)
|
||||||
|
{
|
||||||
|
const timeMs_t currentTimeMs = currentTimeUs / 1000;
|
||||||
|
|
||||||
|
if (!escSensorEnabled) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
// Wait period of time before requesting telemetry (let the system boot first)
|
||||||
|
if (currentTimeMs < ESC_BOOTTIME) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
else if (escSensorTriggerState == ESC_SENSOR_TRIGGER_WAIT) {
|
||||||
|
// Ready for starting requesting telemetry
|
||||||
|
escSensorTriggerState = ESC_SENSOR_TRIGGER_READY;
|
||||||
|
escSensorMotor = 0;
|
||||||
|
escTriggerTimestamp = currentTimeMs;
|
||||||
|
escLastResponseTimestamp = escTriggerTimestamp;
|
||||||
|
}
|
||||||
|
else if (escSensorTriggerState == ESC_SENSOR_TRIGGER_READY) {
|
||||||
|
DEBUG_SET(DEBUG_ESC_SENSOR, 0, escSensorMotor+1);
|
||||||
|
|
||||||
|
motorDmaOutput_t * const motor = getMotorDmaOutput(escSensorMotor);
|
||||||
|
motor->requestTelemetry = true;
|
||||||
|
escSensorTriggerState = ESC_SENSOR_TRIGGER_PENDING;
|
||||||
|
}
|
||||||
|
else if (escSensorTriggerState == ESC_SENSOR_TRIGGER_PENDING) {
|
||||||
|
|
||||||
|
if (escTriggerTimestamp + ESC_REQUEST_TIMEOUT < currentTimeMs) {
|
||||||
|
// ESC did not repond in time, retry
|
||||||
|
timeoutRetryCount++;
|
||||||
|
escTriggerTimestamp = currentTimeMs;
|
||||||
|
escSensorTriggerState = ESC_SENSOR_TRIGGER_READY;
|
||||||
|
|
||||||
|
if (timeoutRetryCount == 4) {
|
||||||
|
// Not responding after 3 times, skip motor
|
||||||
|
escSensorData[escSensorMotor].skipped = true;
|
||||||
|
selectNextMotor();
|
||||||
|
}
|
||||||
|
|
||||||
|
DEBUG_SET(DEBUG_ESC_SENSOR, 1, ++totalRetryCount);
|
||||||
|
}
|
||||||
|
|
||||||
|
// Get received frame status
|
||||||
|
uint8_t state = escSensorFrameStatus();
|
||||||
|
|
||||||
|
if (state == ESC_SENSOR_FRAME_COMPLETE) {
|
||||||
|
// Wait until all ESCs are processed
|
||||||
|
if (escSensorMotor == getMotorCount()-1) {
|
||||||
|
escCurrent = 0;
|
||||||
|
escConsumption = 0;
|
||||||
|
escVbat = 0;
|
||||||
|
|
||||||
|
for (int i = 0; i < getMotorCount(); i++) {
|
||||||
|
if (!escSensorData[i].skipped) {
|
||||||
|
escVbat = i > 0 ? ((escVbat + escSensorData[i].voltage) / 2) : escSensorData[i].voltage;
|
||||||
|
escCurrent = escCurrent + escSensorData[i].current;
|
||||||
|
escConsumption = escConsumption + escSensorData[i].consumption;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
DEBUG_SET(DEBUG_ESC_SENSOR, 2, escVbat);
|
||||||
|
DEBUG_SET(DEBUG_ESC_SENSOR, 3, escCurrent);
|
||||||
|
|
||||||
|
selectNextMotor();
|
||||||
|
escSensorTriggerState = ESC_SENSOR_TRIGGER_READY;
|
||||||
|
escLastResponseTimestamp = currentTimeMs;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
if (escLastResponseTimestamp + 10000 < currentTimeMs) {
|
||||||
|
// ESCs did not respond for 10 seconds
|
||||||
|
// Disable ESC telemetry and reset voltage and current to let the use know something is wrong
|
||||||
|
freeEscSensorPort();
|
||||||
|
escVbat = 0;
|
||||||
|
escCurrent = 0;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
static void selectNextMotor(void)
|
||||||
|
{
|
||||||
|
escSensorMotor++;
|
||||||
|
if (escSensorMotor == getMotorCount()) {
|
||||||
|
escSensorMotor = 0;
|
||||||
|
}
|
||||||
|
timeoutRetryCount = 0;
|
||||||
|
escTriggerTimestamp = millis();
|
||||||
|
}
|
||||||
|
|
||||||
|
//-- CRC
|
||||||
|
|
||||||
|
static uint8_t update_crc8(uint8_t crc, uint8_t crc_seed)
|
||||||
|
{
|
||||||
|
uint8_t crc_u = crc;
|
||||||
|
crc_u ^= crc_seed;
|
||||||
|
|
||||||
|
for (int i=0; i<8; i++) {
|
||||||
|
crc_u = ( crc_u & 0x80 ) ? 0x7 ^ ( crc_u << 1 ) : ( crc_u << 1 );
|
||||||
|
}
|
||||||
|
|
||||||
|
return (crc_u);
|
||||||
|
}
|
||||||
|
|
||||||
|
static uint8_t get_crc8(uint8_t *Buf, uint8_t BufLen)
|
||||||
|
{
|
||||||
|
uint8_t crc = 0;
|
||||||
|
for(int i=0; i<BufLen; i++) crc = update_crc8(Buf[i], crc);
|
||||||
|
return (crc);
|
||||||
|
}
|
||||||
|
|
||||||
|
#endif
|
10
src/main/sensors/esc_sensor.h
Normal file
10
src/main/sensors/esc_sensor.h
Normal file
|
@ -0,0 +1,10 @@
|
||||||
|
#pragma once
|
||||||
|
|
||||||
|
uint8_t escSensorFrameStatus(void);
|
||||||
|
bool escSensorInit(void);
|
||||||
|
bool isEscSensorActive(void);
|
||||||
|
int16_t getEscSensorVbat(void);
|
||||||
|
int16_t getEscSensorCurrent(void);
|
||||||
|
int16_t getEscSensorConsumption(void);
|
||||||
|
|
||||||
|
void escSensorProcess(uint32_t currentTime);
|
|
@ -91,7 +91,7 @@ bool sensorsAutodetect(const gyroConfig_t *gyroConfig,
|
||||||
|
|
||||||
const extiConfig_t *extiConfig = selectMPUIntExtiConfig();
|
const extiConfig_t *extiConfig = selectMPUIntExtiConfig();
|
||||||
|
|
||||||
mpuDetectionResult_t *mpuDetectionResult = detectMpu(extiConfig);
|
mpuDetectionResult_t *mpuDetectionResult = mpuDetect(extiConfig);
|
||||||
UNUSED(mpuDetectionResult);
|
UNUSED(mpuDetectionResult);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
|
@ -2,9 +2,10 @@
|
||||||
|
|
||||||
AlienWii is now AlienFlight. This targets supports various variants of brushed and brushless flight controllers. The designs for them are released partially for public use at:
|
AlienWii is now AlienFlight. This targets supports various variants of brushed and brushless flight controllers. The designs for them are released partially for public use at:
|
||||||
|
|
||||||
|
http://www.alienflight.com
|
||||||
http://www.alienflightng.com
|
http://www.alienflightng.com
|
||||||
|
|
||||||
The legacy designs are available at:
|
AlienFlight Classic and F3 Eagle files are available at:
|
||||||
|
|
||||||
https://github.com/MJ666/Flight-Controllers
|
https://github.com/MJ666/Flight-Controllers
|
||||||
|
|
||||||
|
|
|
@ -33,7 +33,7 @@
|
||||||
#include "config/config_profile.h"
|
#include "config/config_profile.h"
|
||||||
#include "config/config_master.h"
|
#include "config/config_master.h"
|
||||||
|
|
||||||
#include "hardware_revision.h"
|
#define BRUSHED_MOTORS_PWM_RATE 32000 // 32kHz
|
||||||
|
|
||||||
// alternative defaults settings for AlienFlight targets
|
// alternative defaults settings for AlienFlight targets
|
||||||
void targetConfiguration(master_t *config)
|
void targetConfiguration(master_t *config)
|
||||||
|
@ -42,10 +42,7 @@ void targetConfiguration(master_t *config)
|
||||||
config->rxConfig.spektrum_sat_bind_autoreset = 1;
|
config->rxConfig.spektrum_sat_bind_autoreset = 1;
|
||||||
|
|
||||||
if (hardwareMotorType == MOTOR_BRUSHED) {
|
if (hardwareMotorType == MOTOR_BRUSHED) {
|
||||||
config->motorConfig.minthrottle = 1000;
|
config->motorConfig.motorPwmRate = BRUSHED_MOTORS_PWM_RATE;
|
||||||
config->motorConfig.motorPwmRate = 32000;
|
|
||||||
config->motorConfig.motorPwmProtocol = PWM_TYPE_BRUSHED;
|
|
||||||
config->motorConfig.useUnsyncedPwm = true;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
config->profile[0].pidProfile.P8[ROLL] = 90;
|
config->profile[0].pidProfile.P8[ROLL] = 90;
|
||||||
|
|
|
@ -20,8 +20,7 @@
|
||||||
#define TARGET_BOARD_IDENTIFIER "AFF1" // AlienFlight F1.
|
#define TARGET_BOARD_IDENTIFIER "AFF1" // AlienFlight F1.
|
||||||
#define TARGET_CONFIG
|
#define TARGET_CONFIG
|
||||||
|
|
||||||
#define USE_HARDWARE_REVISION_DETECTION
|
#define BRUSHED_ESC_AUTODETECT
|
||||||
#define MOTOR_PIN PA8
|
|
||||||
|
|
||||||
#define LED0 PB3
|
#define LED0 PB3
|
||||||
#define LED1 PB4
|
#define LED1 PB4
|
||||||
|
|
|
@ -2,9 +2,10 @@
|
||||||
|
|
||||||
AlienWii is now AlienFlight. This targets supports various variants of brushed and brushless flight controllers. The designs for them are released partially for public use at:
|
AlienWii is now AlienFlight. This targets supports various variants of brushed and brushless flight controllers. The designs for them are released partially for public use at:
|
||||||
|
|
||||||
|
http://www.alienflight.com
|
||||||
http://www.alienflightng.com
|
http://www.alienflightng.com
|
||||||
|
|
||||||
The legacy designs are available at:
|
AlienFlight Classic and F3 Eagle files are available at:
|
||||||
|
|
||||||
https://github.com/MJ666/Flight-Controllers
|
https://github.com/MJ666/Flight-Controllers
|
||||||
|
|
||||||
|
|
|
@ -42,19 +42,46 @@
|
||||||
|
|
||||||
#include "hardware_revision.h"
|
#include "hardware_revision.h"
|
||||||
|
|
||||||
|
#define BRUSHED_MOTORS_PWM_RATE 32000 // 32kHz
|
||||||
|
|
||||||
// alternative defaults settings for AlienFlight targets
|
// alternative defaults settings for AlienFlight targets
|
||||||
void targetConfiguration(master_t *config)
|
void targetConfiguration(master_t *config)
|
||||||
{
|
{
|
||||||
|
/* depending on revision ... depends on the LEDs to be utilised. */
|
||||||
|
if (hardwareRevision == AFF3_REV_2) {
|
||||||
|
config->statusLedConfig.polarity = 0
|
||||||
|
#ifdef LED0_A_INVERTED
|
||||||
|
| BIT(0)
|
||||||
|
#endif
|
||||||
|
#ifdef LED1_A_INVERTED
|
||||||
|
| BIT(1)
|
||||||
|
#endif
|
||||||
|
#ifdef LED2_A_INVERTED
|
||||||
|
| BIT(2)
|
||||||
|
#endif
|
||||||
|
;
|
||||||
|
|
||||||
|
for (int i = 0; i < LED_NUMBER; i++) {
|
||||||
|
config->statusLedConfig.ledTags[i] = IO_TAG_NONE;
|
||||||
|
}
|
||||||
|
#ifdef LED0_A
|
||||||
|
config->statusLedConfig.ledTags[0] = IO_TAG(LED0_A);
|
||||||
|
#endif
|
||||||
|
#ifdef LED1_A
|
||||||
|
config->statusLedConfig.ledTags[1] = IO_TAG(LED1_A);
|
||||||
|
#endif
|
||||||
|
#ifdef LED2_A
|
||||||
|
config->statusLedConfig.ledTags[2] = IO_TAG(LED2_A);
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
config->rxConfig.spektrum_sat_bind = 5;
|
config->rxConfig.spektrum_sat_bind = 5;
|
||||||
config->rxConfig.spektrum_sat_bind_autoreset = 1;
|
config->rxConfig.spektrum_sat_bind_autoreset = 1;
|
||||||
config->compassConfig.mag_hardware = MAG_NONE; // disabled by default
|
config->compassConfig.mag_hardware = MAG_NONE; // disabled by default
|
||||||
|
|
||||||
if (hardwareMotorType == MOTOR_BRUSHED) {
|
if (hardwareMotorType == MOTOR_BRUSHED) {
|
||||||
config->motorConfig.minthrottle = 1000;
|
config->motorConfig.motorPwmRate = BRUSHED_MOTORS_PWM_RATE;
|
||||||
config->motorConfig.motorPwmRate = 32000;
|
|
||||||
config->motorConfig.motorPwmProtocol = PWM_TYPE_BRUSHED;
|
|
||||||
config->pid_process_denom = 2;
|
config->pid_process_denom = 2;
|
||||||
config->motorConfig.useUnsyncedPwm = true;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
config->profile[0].pidProfile.P8[ROLL] = 90;
|
config->profile[0].pidProfile.P8[ROLL] = 90;
|
||||||
|
|
|
@ -29,10 +29,8 @@
|
||||||
#include "hardware_revision.h"
|
#include "hardware_revision.h"
|
||||||
|
|
||||||
uint8_t hardwareRevision = AFF3_UNKNOWN;
|
uint8_t hardwareRevision = AFF3_UNKNOWN;
|
||||||
uint8_t hardwareMotorType = MOTOR_UNKNOWN;
|
|
||||||
|
|
||||||
static IO_t HWDetectPin = IO_NONE;
|
static IO_t HWDetectPin = IO_NONE;
|
||||||
static IO_t MotorDetectPin = IO_NONE;
|
|
||||||
|
|
||||||
void detectHardwareRevision(void)
|
void detectHardwareRevision(void)
|
||||||
{
|
{
|
||||||
|
@ -40,10 +38,6 @@ void detectHardwareRevision(void)
|
||||||
IOInit(HWDetectPin, OWNER_SYSTEM, 0);
|
IOInit(HWDetectPin, OWNER_SYSTEM, 0);
|
||||||
IOConfigGPIO(HWDetectPin, IOCFG_IPU);
|
IOConfigGPIO(HWDetectPin, IOCFG_IPU);
|
||||||
|
|
||||||
MotorDetectPin = IOGetByTag(IO_TAG(MOTOR_PIN));
|
|
||||||
IOInit(MotorDetectPin, OWNER_SYSTEM, 0);
|
|
||||||
IOConfigGPIO(MotorDetectPin, IOCFG_IPU);
|
|
||||||
|
|
||||||
delayMicroseconds(10); // allow configuration to settle
|
delayMicroseconds(10); // allow configuration to settle
|
||||||
|
|
||||||
// Check hardware revision
|
// Check hardware revision
|
||||||
|
@ -52,13 +46,6 @@ void detectHardwareRevision(void)
|
||||||
} else {
|
} else {
|
||||||
hardwareRevision = AFF3_REV_2;
|
hardwareRevision = AFF3_REV_2;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Check presence of brushed ESC's
|
|
||||||
if (IORead(MotorDetectPin)) {
|
|
||||||
hardwareMotorType = MOTOR_BRUSHLESS;
|
|
||||||
} else {
|
|
||||||
hardwareMotorType = MOTOR_BRUSHED;
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void updateHardwareRevision(void)
|
void updateHardwareRevision(void)
|
||||||
|
|
|
@ -22,14 +22,7 @@ typedef enum awf3HardwareRevision_t {
|
||||||
AFF3_REV_2 // MPU6500 / MPU9250 (SPI)
|
AFF3_REV_2 // MPU6500 / MPU9250 (SPI)
|
||||||
} awf3HardwareRevision_e;
|
} awf3HardwareRevision_e;
|
||||||
|
|
||||||
typedef enum awf4HardwareMotorType_t {
|
|
||||||
MOTOR_UNKNOWN = 0,
|
|
||||||
MOTOR_BRUSHED,
|
|
||||||
MOTOR_BRUSHLESS
|
|
||||||
} awf4HardwareMotorType_e;
|
|
||||||
|
|
||||||
extern uint8_t hardwareRevision;
|
extern uint8_t hardwareRevision;
|
||||||
extern uint8_t hardwareMotorType;
|
|
||||||
|
|
||||||
void updateHardwareRevision(void);
|
void updateHardwareRevision(void);
|
||||||
void detectHardwareRevision(void);
|
void detectHardwareRevision(void);
|
||||||
|
|
48
src/main/target/ALIENFLIGHTF3/initialisation.c
Normal file
48
src/main/target/ALIENFLIGHTF3/initialisation.c
Normal file
|
@ -0,0 +1,48 @@
|
||||||
|
/*
|
||||||
|
* This file is part of Cleanflight.
|
||||||
|
*
|
||||||
|
* Cleanflight is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* Cleanflight is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*/
|
||||||
|
|
||||||
|
#include <stdbool.h>
|
||||||
|
#include <stdint.h>
|
||||||
|
|
||||||
|
#include "platform.h"
|
||||||
|
#include "drivers/bus_i2c.h"
|
||||||
|
#include "drivers/bus_spi.h"
|
||||||
|
#include "hardware_revision.h"
|
||||||
|
|
||||||
|
void targetBusInit(void)
|
||||||
|
{
|
||||||
|
#ifdef USE_SPI
|
||||||
|
#ifdef USE_SPI_DEVICE_1
|
||||||
|
spiInit(SPIDEV_1);
|
||||||
|
#endif
|
||||||
|
#ifdef USE_SPI_DEVICE_2
|
||||||
|
spiInit(SPIDEV_2);
|
||||||
|
#endif
|
||||||
|
#ifdef USE_SPI_DEVICE_3
|
||||||
|
if (hardwareRevision == AFF3_REV_2) {
|
||||||
|
spiInit(SPIDEV_3);
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
#ifdef USE_SPI_DEVICE_4
|
||||||
|
spiInit(SPIDEV_4);
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef USE_I2C
|
||||||
|
i2cInit(I2C_DEVICE);
|
||||||
|
#endif
|
||||||
|
}
|
|
@ -19,12 +19,13 @@
|
||||||
|
|
||||||
#define TARGET_BOARD_IDENTIFIER "AFF3" // AlienFlight F3.
|
#define TARGET_BOARD_IDENTIFIER "AFF3" // AlienFlight F3.
|
||||||
#define TARGET_CONFIG
|
#define TARGET_CONFIG
|
||||||
|
#define TARGET_BUS_INIT
|
||||||
|
|
||||||
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT
|
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT
|
||||||
|
|
||||||
#define USE_HARDWARE_REVISION_DETECTION
|
#define USE_HARDWARE_REVISION_DETECTION
|
||||||
#define HW_PIN PB2
|
#define HW_PIN PB2
|
||||||
#define MOTOR_PIN PB15
|
#define BRUSHED_ESC_AUTODETECT
|
||||||
|
|
||||||
// LED's V1
|
// LED's V1
|
||||||
#define LED0 PB4
|
#define LED0 PB4
|
||||||
|
|
|
@ -2,9 +2,10 @@
|
||||||
|
|
||||||
AlienWii is now AlienFlight. This targets supports various variants of brushed and brushless flight controllers. The designs for them are released partially for public use at:
|
AlienWii is now AlienFlight. This targets supports various variants of brushed and brushless flight controllers. The designs for them are released partially for public use at:
|
||||||
|
|
||||||
|
http://www.alienflight.com
|
||||||
http://www.alienflightng.com
|
http://www.alienflightng.com
|
||||||
|
|
||||||
The legacy designs are available at:
|
AlienFlight Classic and F3 Eagle files are available at:
|
||||||
|
|
||||||
https://github.com/MJ666/Flight-Controllers
|
https://github.com/MJ666/Flight-Controllers
|
||||||
|
|
||||||
|
|
|
@ -61,11 +61,8 @@ void targetConfiguration(master_t *config)
|
||||||
config->compassConfig.mag_hardware = MAG_NONE; // disabled by default
|
config->compassConfig.mag_hardware = MAG_NONE; // disabled by default
|
||||||
|
|
||||||
if (hardwareMotorType == MOTOR_BRUSHED) {
|
if (hardwareMotorType == MOTOR_BRUSHED) {
|
||||||
config->motorConfig.minthrottle = 1000;
|
|
||||||
config->motorConfig.motorPwmRate = BRUSHED_MOTORS_PWM_RATE;
|
config->motorConfig.motorPwmRate = BRUSHED_MOTORS_PWM_RATE;
|
||||||
config->motorConfig.motorPwmProtocol = PWM_TYPE_BRUSHED;
|
|
||||||
config->pid_process_denom = 1;
|
config->pid_process_denom = 1;
|
||||||
config->motorConfig.useUnsyncedPwm = true;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
if (hardwareRevision == AFF4_REV_1) {
|
if (hardwareRevision == AFF4_REV_1) {
|
||||||
|
|
|
@ -28,10 +28,8 @@
|
||||||
#include "hardware_revision.h"
|
#include "hardware_revision.h"
|
||||||
|
|
||||||
uint8_t hardwareRevision = AFF4_UNKNOWN;
|
uint8_t hardwareRevision = AFF4_UNKNOWN;
|
||||||
uint8_t hardwareMotorType = MOTOR_UNKNOWN;
|
|
||||||
|
|
||||||
static IO_t HWDetectPin = IO_NONE;
|
static IO_t HWDetectPin = IO_NONE;
|
||||||
static IO_t MotorDetectPin = IO_NONE;
|
|
||||||
|
|
||||||
void detectHardwareRevision(void)
|
void detectHardwareRevision(void)
|
||||||
{
|
{
|
||||||
|
@ -39,10 +37,6 @@ void detectHardwareRevision(void)
|
||||||
IOInit(HWDetectPin, OWNER_SYSTEM, 0);
|
IOInit(HWDetectPin, OWNER_SYSTEM, 0);
|
||||||
IOConfigGPIO(HWDetectPin, IOCFG_IPU);
|
IOConfigGPIO(HWDetectPin, IOCFG_IPU);
|
||||||
|
|
||||||
MotorDetectPin = IOGetByTag(IO_TAG(MOTOR_PIN));
|
|
||||||
IOInit(MotorDetectPin, OWNER_SYSTEM, 0);
|
|
||||||
IOConfigGPIO(MotorDetectPin, IOCFG_IPU);
|
|
||||||
|
|
||||||
delayMicroseconds(10); // allow configuration to settle
|
delayMicroseconds(10); // allow configuration to settle
|
||||||
|
|
||||||
// Check hardware revision
|
// Check hardware revision
|
||||||
|
@ -51,13 +45,6 @@ void detectHardwareRevision(void)
|
||||||
} else {
|
} else {
|
||||||
hardwareRevision = AFF4_REV_2;
|
hardwareRevision = AFF4_REV_2;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Check presence of brushed ESC's
|
|
||||||
if (IORead(MotorDetectPin)) {
|
|
||||||
hardwareMotorType = MOTOR_BRUSHLESS;
|
|
||||||
} else {
|
|
||||||
hardwareMotorType = MOTOR_BRUSHED;
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void updateHardwareRevision(void)
|
void updateHardwareRevision(void)
|
||||||
|
|
|
@ -22,14 +22,7 @@ typedef enum awf4HardwareRevision_t {
|
||||||
AFF4_REV_2 // ICM-20602 (SPI), OpenSky RX (CC2510), Current Sensor (ACS712), SDCard Reader
|
AFF4_REV_2 // ICM-20602 (SPI), OpenSky RX (CC2510), Current Sensor (ACS712), SDCard Reader
|
||||||
} awf4HardwareRevision_e;
|
} awf4HardwareRevision_e;
|
||||||
|
|
||||||
typedef enum awf4HardwareMotorType_t {
|
|
||||||
MOTOR_UNKNOWN = 0,
|
|
||||||
MOTOR_BRUSHED,
|
|
||||||
MOTOR_BRUSHLESS
|
|
||||||
} awf4HardwareMotorType_e;
|
|
||||||
|
|
||||||
extern uint8_t hardwareRevision;
|
extern uint8_t hardwareRevision;
|
||||||
extern uint8_t hardwareMotorType;
|
|
||||||
|
|
||||||
void updateHardwareRevision(void);
|
void updateHardwareRevision(void);
|
||||||
void detectHardwareRevision(void);
|
void detectHardwareRevision(void);
|
||||||
|
|
|
@ -21,7 +21,7 @@
|
||||||
|
|
||||||
#define USE_HARDWARE_REVISION_DETECTION
|
#define USE_HARDWARE_REVISION_DETECTION
|
||||||
#define HW_PIN PC13
|
#define HW_PIN PC13
|
||||||
#define MOTOR_PIN PB8
|
#define BRUSHED_ESC_AUTODETECT
|
||||||
|
|
||||||
#define CONFIG_START_FLASH_ADDRESS (0x08080000) //0x08080000 to 0x080A0000 (FLASH_Sector_8)
|
#define CONFIG_START_FLASH_ADDRESS (0x08080000) //0x08080000 to 0x080A0000 (FLASH_Sector_8)
|
||||||
|
|
||||||
|
|
|
@ -24,7 +24,7 @@
|
||||||
#define USBD_PRODUCT_STRING "AnyFCF7"
|
#define USBD_PRODUCT_STRING "AnyFCF7"
|
||||||
|
|
||||||
#define USE_DSHOT
|
#define USE_DSHOT
|
||||||
#define USE_ESC_TELEMETRY
|
#define USE_ESC_SENSOR
|
||||||
|
|
||||||
#define LED0 PB7
|
#define LED0 PB7
|
||||||
#define LED1 PB6
|
#define LED1 PB6
|
||||||
|
|
|
@ -44,7 +44,8 @@
|
||||||
#define MPU_INT_EXTI PC13
|
#define MPU_INT_EXTI PC13
|
||||||
#define USE_EXTI
|
#define USE_EXTI
|
||||||
|
|
||||||
#define USE_ESC_TELEMETRY
|
#define USE_DSHOT
|
||||||
|
#define USE_ESC_SENSOR
|
||||||
#define REMAP_TIM16_DMA
|
#define REMAP_TIM16_DMA
|
||||||
#define REMAP_TIM17_DMA
|
#define REMAP_TIM17_DMA
|
||||||
|
|
||||||
|
|
|
@ -85,7 +85,8 @@ void updateHardwareRevision(void)
|
||||||
/*
|
/*
|
||||||
if flash exists on PB3 then Rev1
|
if flash exists on PB3 then Rev1
|
||||||
*/
|
*/
|
||||||
if (m25p16_init(IO_TAG(PB3))) {
|
flashConfig_t flashConfig = { .csTag = IO_TAG(PB3) };
|
||||||
|
if (m25p16_init(&flashConfig)) {
|
||||||
hardwareRevision = BJF4_REV1;
|
hardwareRevision = BJF4_REV1;
|
||||||
} else {
|
} else {
|
||||||
IOInit(IOGetByTag(IO_TAG(PB3)), OWNER_FREE, 0);
|
IOInit(IOGetByTag(IO_TAG(PB3)), OWNER_FREE, 0);
|
||||||
|
|
|
@ -144,7 +144,8 @@
|
||||||
#define USE_ADC
|
#define USE_ADC
|
||||||
#define VBAT_ADC_PIN PC3
|
#define VBAT_ADC_PIN PC3
|
||||||
|
|
||||||
#define USE_ESC_TELEMETRY
|
#define USE_DSHOT
|
||||||
|
#define USE_ESC_SENSOR
|
||||||
#define LED_STRIP
|
#define LED_STRIP
|
||||||
|
|
||||||
#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
|
#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
|
||||||
|
|
|
@ -14,24 +14,23 @@
|
||||||
* You should have received a copy of the GNU General Public License
|
* You should have received a copy of the GNU General Public License
|
||||||
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||||
*/
|
*/
|
||||||
#pragma once
|
|
||||||
|
|
||||||
typedef enum awf1HardwareRevision_t {
|
#include <stdbool.h>
|
||||||
AFF1_UNKNOWN = 0,
|
#include <stdint.h>
|
||||||
AFF1_REV_1, // MPU6050 (I2C)
|
|
||||||
} awf1HardwareRevision_e;
|
|
||||||
|
|
||||||
typedef enum awf4HardwareMotorType_t {
|
#include "platform.h"
|
||||||
MOTOR_UNKNOWN = 0,
|
#include "drivers/bus_i2c.h"
|
||||||
MOTOR_BRUSHED,
|
#include "drivers/bus_spi.h"
|
||||||
MOTOR_BRUSHLESS
|
#include "io/serial.h"
|
||||||
} awf4HardwareMotorType_e;
|
|
||||||
|
|
||||||
extern uint8_t hardwareRevision;
|
void targetBusInit(void)
|
||||||
extern uint8_t hardwareMotorType;
|
{
|
||||||
|
#if defined(USE_SPI) && defined(USE_SPI_DEVICE_1)
|
||||||
|
spiInit(SPIDEV_1);
|
||||||
|
#endif
|
||||||
|
|
||||||
void updateHardwareRevision(void);
|
if (!doesConfigurationUsePort(SERIAL_PORT_USART3)) {
|
||||||
void detectHardwareRevision(void);
|
serialRemovePort(SERIAL_PORT_USART3);
|
||||||
|
i2cInit(I2C_DEVICE);
|
||||||
struct extiConfig_s;
|
}
|
||||||
const struct extiConfig_s *selectMPUIntExtiConfigByHardwareRevision(void);
|
}
|
|
@ -19,6 +19,7 @@
|
||||||
|
|
||||||
#define TARGET_BOARD_IDENTIFIER "CJM1" // CJMCU
|
#define TARGET_BOARD_IDENTIFIER "CJM1" // CJMCU
|
||||||
#define USE_HARDWARE_REVISION_DETECTION
|
#define USE_HARDWARE_REVISION_DETECTION
|
||||||
|
#define TARGET_BUS_INIT
|
||||||
|
|
||||||
#define LED0 PC14
|
#define LED0 PC14
|
||||||
#define LED1 PC13
|
#define LED1 PC13
|
||||||
|
|
|
@ -125,7 +125,8 @@
|
||||||
#define ENSURE_MPU_DATA_READY_IS_LOW
|
#define ENSURE_MPU_DATA_READY_IS_LOW
|
||||||
|
|
||||||
#define LED_STRIP
|
#define LED_STRIP
|
||||||
#define USE_ESC_TELEMETRY
|
#define USE_DSHOT
|
||||||
|
#define USE_ESC_SENSOR
|
||||||
|
|
||||||
#define DEFAULT_RX_FEATURE FEATURE_RX_PPM
|
#define DEFAULT_RX_FEATURE FEATURE_RX_PPM
|
||||||
|
|
||||||
|
|
|
@ -161,7 +161,8 @@
|
||||||
|
|
||||||
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||||
|
|
||||||
#define USE_ESC_TELEMETRY
|
#define USE_DSHOT
|
||||||
|
#define USE_ESC_SENSOR
|
||||||
#define REMAP_TIM17_DMA
|
#define REMAP_TIM17_DMA
|
||||||
|
|
||||||
#define TARGET_IO_PORTA 0xffff
|
#define TARGET_IO_PORTA 0xffff
|
||||||
|
|
|
@ -175,7 +175,8 @@
|
||||||
|
|
||||||
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||||
|
|
||||||
#define USE_ESC_TELEMETRY
|
#define USE_DSHOT
|
||||||
|
#define USE_ESC_SENSOR
|
||||||
|
|
||||||
#define TARGET_IO_PORTA 0xffff
|
#define TARGET_IO_PORTA 0xffff
|
||||||
#define TARGET_IO_PORTB 0xffff
|
#define TARGET_IO_PORTB 0xffff
|
||||||
|
|
|
@ -24,7 +24,7 @@
|
||||||
#define USBD_PRODUCT_STRING "FuryF7"
|
#define USBD_PRODUCT_STRING "FuryF7"
|
||||||
|
|
||||||
#define USE_DSHOT
|
#define USE_DSHOT
|
||||||
#define USE_ESC_TELEMETRY
|
#define USE_ESC_SENSOR
|
||||||
|
|
||||||
#define LED0 PB5
|
#define LED0 PB5
|
||||||
#define LED1 PB4
|
#define LED1 PB4
|
||||||
|
|
|
@ -46,7 +46,8 @@
|
||||||
#define USE_FLASHFS
|
#define USE_FLASHFS
|
||||||
#define USE_FLASH_M25P16
|
#define USE_FLASH_M25P16
|
||||||
|
|
||||||
#define USE_ESC_TELEMETRY
|
#define USE_DSHOT
|
||||||
|
#define USE_ESC_SENSOR
|
||||||
#define REMAP_TIM17_DMA
|
#define REMAP_TIM17_DMA
|
||||||
|
|
||||||
#define USE_VCP
|
#define USE_VCP
|
||||||
|
|
|
@ -23,7 +23,8 @@
|
||||||
|
|
||||||
#define SBUS_PORT_OPTIONS (SERIAL_STOPBITS_2 | SERIAL_PARITY_EVEN | SERIAL_INVERTED | SERIAL_BIDIR)
|
#define SBUS_PORT_OPTIONS (SERIAL_STOPBITS_2 | SERIAL_PARITY_EVEN | SERIAL_INVERTED | SERIAL_BIDIR)
|
||||||
|
|
||||||
#define USE_ESC_TELEMETRY
|
#define USE_DSHOT
|
||||||
|
#define USE_ESC_SENSOR
|
||||||
|
|
||||||
#define USE_ESCSERIAL
|
#define USE_ESCSERIAL
|
||||||
#define ESCSERIAL_TIMER_TX_HARDWARE 6
|
#define ESCSERIAL_TIMER_TX_HARDWARE 6
|
||||||
|
|
|
@ -46,7 +46,8 @@
|
||||||
#define USE_MPU_DATA_READY_SIGNAL
|
#define USE_MPU_DATA_READY_SIGNAL
|
||||||
#define ENSURE_MPU_DATA_READY_IS_LOW
|
#define ENSURE_MPU_DATA_READY_IS_LOW
|
||||||
|
|
||||||
#define USE_ESC_TELEMETRY
|
#define USE_DSHOT
|
||||||
|
#define USE_ESC_SENSOR
|
||||||
|
|
||||||
#define USE_SPI
|
#define USE_SPI
|
||||||
#define USE_SPI_DEVICE_1
|
#define USE_SPI_DEVICE_1
|
||||||
|
|
|
@ -95,7 +95,8 @@
|
||||||
#define RSSI_ADC_PIN PB2
|
#define RSSI_ADC_PIN PB2
|
||||||
|
|
||||||
#define LED_STRIP
|
#define LED_STRIP
|
||||||
#define USE_ESC_TELEMETRY
|
#define USE_DSHOT
|
||||||
|
#define USE_ESC_SENSOR
|
||||||
|
|
||||||
#define SPEKTRUM_BIND
|
#define SPEKTRUM_BIND
|
||||||
// USART2, PB4
|
// USART2, PB4
|
||||||
|
|
|
@ -105,7 +105,8 @@
|
||||||
#define CURRENT_METER_ADC_PIN PA5
|
#define CURRENT_METER_ADC_PIN PA5
|
||||||
#define RSSI_ADC_PIN PB2
|
#define RSSI_ADC_PIN PB2
|
||||||
|
|
||||||
#define USE_ESC_TELEMETRY
|
#define USE_DSHOT
|
||||||
|
#define USE_ESC_SENSOR
|
||||||
#define REMAP_TIM17_DMA
|
#define REMAP_TIM17_DMA
|
||||||
|
|
||||||
// UART1 TX uses DMA1_Channel4, which is also used by dshot on motor 4
|
// UART1 TX uses DMA1_Channel4, which is also used by dshot on motor 4
|
||||||
|
|
|
@ -35,6 +35,8 @@
|
||||||
|
|
||||||
void targetConfiguration(master_t *config)
|
void targetConfiguration(master_t *config)
|
||||||
{
|
{
|
||||||
|
UNUSED(config);
|
||||||
|
|
||||||
#ifdef BEEBRAIN
|
#ifdef BEEBRAIN
|
||||||
// alternative defaults settings for Beebrain target
|
// alternative defaults settings for Beebrain target
|
||||||
config->motorConfig.motorPwmRate = 4000;
|
config->motorConfig.motorPwmRate = 4000;
|
||||||
|
@ -88,9 +90,8 @@ void targetConfiguration(master_t *config)
|
||||||
} else {
|
} else {
|
||||||
config->beeperConfig.isOpenDrain = true;
|
config->beeperConfig.isOpenDrain = true;
|
||||||
config->beeperConfig.isInverted = false;
|
config->beeperConfig.isInverted = false;
|
||||||
|
config->flashConfig.csTag = IO_TAG_NONE;
|
||||||
}
|
}
|
||||||
#else
|
|
||||||
UNUSED(config);
|
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -127,3 +127,4 @@ const extiConfig_t *selectMPUIntExtiConfigByHardwareRevision(void)
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -17,43 +17,28 @@
|
||||||
|
|
||||||
#include <stdbool.h>
|
#include <stdbool.h>
|
||||||
#include <stdint.h>
|
#include <stdint.h>
|
||||||
#include <stdlib.h>
|
|
||||||
|
|
||||||
#include "platform.h"
|
#include "platform.h"
|
||||||
|
#include "drivers/bus_i2c.h"
|
||||||
#include "build/build_config.h"
|
#include "drivers/bus_spi.h"
|
||||||
|
#include "io/serial.h"
|
||||||
#include "drivers/system.h"
|
|
||||||
#include "drivers/io.h"
|
|
||||||
#include "drivers/exti.h"
|
|
||||||
#include "hardware_revision.h"
|
#include "hardware_revision.h"
|
||||||
|
|
||||||
uint8_t hardwareRevision = AFF1_REV_1;
|
void targetBusInit(void)
|
||||||
uint8_t hardwareMotorType = MOTOR_UNKNOWN;
|
|
||||||
|
|
||||||
static IO_t MotorDetectPin = IO_NONE;
|
|
||||||
|
|
||||||
void detectHardwareRevision(void)
|
|
||||||
{
|
{
|
||||||
MotorDetectPin = IOGetByTag(IO_TAG(MOTOR_PIN));
|
#ifdef USE_SPI
|
||||||
IOInit(MotorDetectPin, OWNER_SYSTEM, 0);
|
#ifdef USE_SPI_DEVICE_2
|
||||||
IOConfigGPIO(MotorDetectPin, IOCFG_IPU);
|
spiInit(SPIDEV_2);
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
|
||||||
delayMicroseconds(10); // allow configuration to settle
|
if (hardwareRevision != NAZE32_SP) {
|
||||||
|
i2cInit(I2C_DEVICE);
|
||||||
// Check presence of brushed ESC's
|
serialRemovePort(SERIAL_PORT_SOFTSERIAL2);
|
||||||
if (IORead(MotorDetectPin)) {
|
|
||||||
hardwareMotorType = MOTOR_BRUSHLESS;
|
|
||||||
} else {
|
} else {
|
||||||
hardwareMotorType = MOTOR_BRUSHED;
|
if (!doesConfigurationUsePort(SERIAL_PORT_USART3)) {
|
||||||
|
serialRemovePort(SERIAL_PORT_USART3);
|
||||||
|
i2cInit(I2C_DEVICE);
|
||||||
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void updateHardwareRevision(void)
|
|
||||||
{
|
|
||||||
}
|
|
||||||
|
|
||||||
const extiConfig_t *selectMPUIntExtiConfigByHardwareRevision(void)
|
|
||||||
{
|
|
||||||
return NULL;
|
|
||||||
}
|
|
|
@ -19,6 +19,7 @@
|
||||||
|
|
||||||
#define TARGET_CONFIG
|
#define TARGET_CONFIG
|
||||||
#define USE_HARDWARE_REVISION_DETECTION
|
#define USE_HARDWARE_REVISION_DETECTION
|
||||||
|
#define TARGET_BUS_INIT
|
||||||
|
|
||||||
#define CLI_MINIMAL_VERBOSITY
|
#define CLI_MINIMAL_VERBOSITY
|
||||||
|
|
||||||
|
@ -65,17 +66,12 @@
|
||||||
#define USE_SPI_DEVICE_2
|
#define USE_SPI_DEVICE_2
|
||||||
|
|
||||||
#define NAZE_SPI_INSTANCE SPI2
|
#define NAZE_SPI_INSTANCE SPI2
|
||||||
#define NAZE_SPI_CS_GPIO GPIOB
|
|
||||||
#define NAZE_SPI_CS_PIN PB12
|
#define NAZE_SPI_CS_PIN PB12
|
||||||
#define NAZE_CS_GPIO_CLK_PERIPHERAL RCC_APB2Periph_GPIOB
|
|
||||||
|
|
||||||
// We either have this 16mbit flash chip on SPI or the MPU6500 acc/gyro depending on board revision:
|
// We either have this 16mbit flash chip on SPI or the MPU6500 acc/gyro depending on board revision:
|
||||||
#define M25P16_CS_GPIO NAZE_SPI_CS_GPIO
|
|
||||||
#define M25P16_CS_PIN NAZE_SPI_CS_PIN
|
#define M25P16_CS_PIN NAZE_SPI_CS_PIN
|
||||||
#define M25P16_SPI_INSTANCE NAZE_SPI_INSTANCE
|
#define M25P16_SPI_INSTANCE NAZE_SPI_INSTANCE
|
||||||
|
|
||||||
#define MPU6500_CS_GPIO_CLK_PERIPHERAL NAZE_CS_GPIO_CLK_PERIPHERAL
|
|
||||||
#define MPU6500_CS_GPIO NAZE_SPI_CS_GPIO
|
|
||||||
#define MPU6500_CS_PIN NAZE_SPI_CS_PIN
|
#define MPU6500_CS_PIN NAZE_SPI_CS_PIN
|
||||||
#define MPU6500_SPI_INSTANCE NAZE_SPI_INSTANCE
|
#define MPU6500_SPI_INSTANCE NAZE_SPI_INSTANCE
|
||||||
|
|
||||||
|
|
438
src/main/target/NUCLEOF7/stm32f7xx_hal_conf.h
Normal file
438
src/main/target/NUCLEOF7/stm32f7xx_hal_conf.h
Normal file
|
@ -0,0 +1,438 @@
|
||||||
|
/**
|
||||||
|
******************************************************************************
|
||||||
|
* @file stm32f7xx_hal_conf.h
|
||||||
|
* @brief HAL configuration file.
|
||||||
|
******************************************************************************
|
||||||
|
* @attention
|
||||||
|
*
|
||||||
|
* <h2><center>© COPYRIGHT(c) 2016 STMicroelectronics</center></h2>
|
||||||
|
*
|
||||||
|
* Redistribution and use in source and binary forms, with or without modification,
|
||||||
|
* are permitted provided that the following conditions are met:
|
||||||
|
* 1. Redistributions of source code must retain the above copyright notice,
|
||||||
|
* this list of conditions and the following disclaimer.
|
||||||
|
* 2. Redistributions in binary form must reproduce the above copyright notice,
|
||||||
|
* this list of conditions and the following disclaimer in the documentation
|
||||||
|
* and/or other materials provided with the distribution.
|
||||||
|
* 3. Neither the name of STMicroelectronics nor the names of its contributors
|
||||||
|
* may be used to endorse or promote products derived from this software
|
||||||
|
* without specific prior written permission.
|
||||||
|
*
|
||||||
|
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
|
||||||
|
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
|
||||||
|
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
|
||||||
|
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
|
||||||
|
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
|
||||||
|
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
|
||||||
|
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
|
||||||
|
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
|
||||||
|
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
|
||||||
|
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
|
||||||
|
*
|
||||||
|
******************************************************************************
|
||||||
|
*/
|
||||||
|
|
||||||
|
/* Define to prevent recursive inclusion -------------------------------------*/
|
||||||
|
#ifndef __STM32F7xx_HAL_CONF_H
|
||||||
|
#define __STM32F7xx_HAL_CONF_H
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
extern "C" {
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/* Exported types ------------------------------------------------------------*/
|
||||||
|
/* Exported constants --------------------------------------------------------*/
|
||||||
|
|
||||||
|
/* ########################## Module Selection ############################## */
|
||||||
|
/**
|
||||||
|
* @brief This is the list of modules to be used in the HAL driver
|
||||||
|
*/
|
||||||
|
#define HAL_MODULE_ENABLED
|
||||||
|
|
||||||
|
#define HAL_ADC_MODULE_ENABLED
|
||||||
|
/* #define HAL_CAN_MODULE_ENABLED */
|
||||||
|
/* #define HAL_CEC_MODULE_ENABLED */
|
||||||
|
/* #define HAL_CRC_MODULE_ENABLED */
|
||||||
|
/* #define HAL_CRYP_MODULE_ENABLED */
|
||||||
|
/* #define HAL_DAC_MODULE_ENABLED */
|
||||||
|
/* #define HAL_DCMI_MODULE_ENABLED */
|
||||||
|
/* #define HAL_DMA2D_MODULE_ENABLED */
|
||||||
|
/* #define HAL_ETH_MODULE_ENABLED */
|
||||||
|
/* #define HAL_NAND_MODULE_ENABLED */
|
||||||
|
/* #define HAL_NOR_MODULE_ENABLED */
|
||||||
|
/* #define HAL_SRAM_MODULE_ENABLED */
|
||||||
|
/* #define HAL_SDRAM_MODULE_ENABLED */
|
||||||
|
/* #define HAL_HASH_MODULE_ENABLED */
|
||||||
|
/* #define HAL_I2S_MODULE_ENABLED */
|
||||||
|
/* #define HAL_IWDG_MODULE_ENABLED */
|
||||||
|
/* #define HAL_LPTIM_MODULE_ENABLED */
|
||||||
|
/* #define HAL_LTDC_MODULE_ENABLED */
|
||||||
|
/* #define HAL_QSPI_MODULE_ENABLED */
|
||||||
|
/* #define HAL_RNG_MODULE_ENABLED */
|
||||||
|
/* #define HAL_RTC_MODULE_ENABLED */
|
||||||
|
/* #define HAL_SAI_MODULE_ENABLED */
|
||||||
|
/* #define HAL_SD_MODULE_ENABLED */
|
||||||
|
/* #define HAL_SPDIFRX_MODULE_ENABLED */
|
||||||
|
#define HAL_SPI_MODULE_ENABLED
|
||||||
|
#define HAL_TIM_MODULE_ENABLED
|
||||||
|
#define HAL_UART_MODULE_ENABLED
|
||||||
|
#define HAL_USART_MODULE_ENABLED
|
||||||
|
/* #define HAL_IRDA_MODULE_ENABLED */
|
||||||
|
/* #define HAL_SMARTCARD_MODULE_ENABLED */
|
||||||
|
/* #define HAL_WWDG_MODULE_ENABLED */
|
||||||
|
#define HAL_PCD_MODULE_ENABLED
|
||||||
|
/* #define HAL_HCD_MODULE_ENABLED */
|
||||||
|
/* #define HAL_DFSDM_MODULE_ENABLED */
|
||||||
|
/* #define HAL_DSI_MODULE_ENABLED */
|
||||||
|
/* #define HAL_JPEG_MODULE_ENABLED */
|
||||||
|
/* #define HAL_MDIOS_MODULE_ENABLED */
|
||||||
|
#define HAL_GPIO_MODULE_ENABLED
|
||||||
|
#define HAL_DMA_MODULE_ENABLED
|
||||||
|
#define HAL_RCC_MODULE_ENABLED
|
||||||
|
#define HAL_FLASH_MODULE_ENABLED
|
||||||
|
#define HAL_PWR_MODULE_ENABLED
|
||||||
|
#define HAL_I2C_MODULE_ENABLED
|
||||||
|
#define HAL_CORTEX_MODULE_ENABLED
|
||||||
|
|
||||||
|
/* ########################## HSE/HSI Values adaptation ##################### */
|
||||||
|
/**
|
||||||
|
* @brief Adjust the value of External High Speed oscillator (HSE) used in your application.
|
||||||
|
* This value is used by the RCC HAL module to compute the system frequency
|
||||||
|
* (when HSE is used as system clock source, directly or through the PLL).
|
||||||
|
*/
|
||||||
|
#if !defined (HSE_VALUE)
|
||||||
|
#define HSE_VALUE ((uint32_t)8000000U) /*!< Value of the External oscillator in Hz */
|
||||||
|
#endif /* HSE_VALUE */
|
||||||
|
|
||||||
|
#if !defined (HSE_STARTUP_TIMEOUT)
|
||||||
|
#define HSE_STARTUP_TIMEOUT ((uint32_t)100U) /*!< Time out for HSE start up, in ms */
|
||||||
|
#endif /* HSE_STARTUP_TIMEOUT */
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Internal High Speed oscillator (HSI) value.
|
||||||
|
* This value is used by the RCC HAL module to compute the system frequency
|
||||||
|
* (when HSI is used as system clock source, directly or through the PLL).
|
||||||
|
*/
|
||||||
|
#if !defined (HSI_VALUE)
|
||||||
|
#define HSI_VALUE ((uint32_t)16000000U) /*!< Value of the Internal oscillator in Hz*/
|
||||||
|
#endif /* HSI_VALUE */
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Internal Low Speed oscillator (LSI) value.
|
||||||
|
*/
|
||||||
|
#if !defined (LSI_VALUE)
|
||||||
|
#define LSI_VALUE ((uint32_t)32000U) /*!< LSI Typical Value in Hz*/
|
||||||
|
#endif /* LSI_VALUE */ /*!< Value of the Internal Low Speed oscillator in Hz
|
||||||
|
The real value may vary depending on the variations
|
||||||
|
in voltage and temperature. */
|
||||||
|
/**
|
||||||
|
* @brief External Low Speed oscillator (LSE) value.
|
||||||
|
*/
|
||||||
|
#if !defined (LSE_VALUE)
|
||||||
|
#define LSE_VALUE ((uint32_t)32768U) /*!< Value of the External Low Speed oscillator in Hz */
|
||||||
|
#endif /* LSE_VALUE */
|
||||||
|
|
||||||
|
#if !defined (LSE_STARTUP_TIMEOUT)
|
||||||
|
#define LSE_STARTUP_TIMEOUT ((uint32_t)5000U) /*!< Time out for LSE start up, in ms */
|
||||||
|
#endif /* LSE_STARTUP_TIMEOUT */
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief External clock source for I2S peripheral
|
||||||
|
* This value is used by the I2S HAL module to compute the I2S clock source
|
||||||
|
* frequency, this source is inserted directly through I2S_CKIN pad.
|
||||||
|
*/
|
||||||
|
#if !defined (EXTERNAL_CLOCK_VALUE)
|
||||||
|
#define EXTERNAL_CLOCK_VALUE ((uint32_t)12288000U) /*!< Value of the Internal oscillator in Hz*/
|
||||||
|
#endif /* EXTERNAL_CLOCK_VALUE */
|
||||||
|
|
||||||
|
/* Tip: To avoid modifying this file each time you need to use different HSE,
|
||||||
|
=== you can define the HSE value in your toolchain compiler preprocessor. */
|
||||||
|
|
||||||
|
/* ########################### System Configuration ######################### */
|
||||||
|
/**
|
||||||
|
* @brief This is the HAL system configuration section
|
||||||
|
*/
|
||||||
|
#define VDD_VALUE ((uint32_t)3300U) /*!< Value of VDD in mv */
|
||||||
|
#define TICK_INT_PRIORITY ((uint32_t)0U) /*!< tick interrupt priority */
|
||||||
|
#define USE_RTOS 0U
|
||||||
|
#define PREFETCH_ENABLE 0U
|
||||||
|
#define ART_ACCLERATOR_ENABLE 0U /* To enable instruction cache and prefetch */
|
||||||
|
|
||||||
|
/* ########################## Assert Selection ############################## */
|
||||||
|
/**
|
||||||
|
* @brief Uncomment the line below to expanse the "assert_param" macro in the
|
||||||
|
* HAL drivers code
|
||||||
|
*/
|
||||||
|
/* #define USE_FULL_ASSERT 1 */
|
||||||
|
|
||||||
|
/* ################## Ethernet peripheral configuration ##################### */
|
||||||
|
|
||||||
|
/* Section 1 : Ethernet peripheral configuration */
|
||||||
|
|
||||||
|
/* MAC ADDRESS: MAC_ADDR0:MAC_ADDR1:MAC_ADDR2:MAC_ADDR3:MAC_ADDR4:MAC_ADDR5 */
|
||||||
|
#define MAC_ADDR0 2U
|
||||||
|
#define MAC_ADDR1 0U
|
||||||
|
#define MAC_ADDR2 0U
|
||||||
|
#define MAC_ADDR3 0U
|
||||||
|
#define MAC_ADDR4 0U
|
||||||
|
#define MAC_ADDR5 0U
|
||||||
|
|
||||||
|
/* Definition of the Ethernet driver buffers size and count */
|
||||||
|
#define ETH_RX_BUF_SIZE ETH_MAX_PACKET_SIZE /* buffer size for receive */
|
||||||
|
#define ETH_TX_BUF_SIZE ETH_MAX_PACKET_SIZE /* buffer size for transmit */
|
||||||
|
#define ETH_RXBUFNB ((uint32_t)4U) /* 4 Rx buffers of size ETH_RX_BUF_SIZE */
|
||||||
|
#define ETH_TXBUFNB ((uint32_t)4U) /* 4 Tx buffers of size ETH_TX_BUF_SIZE */
|
||||||
|
|
||||||
|
/* Section 2: PHY configuration section */
|
||||||
|
|
||||||
|
/* DP83848_PHY_ADDRESS Address*/
|
||||||
|
#define DP83848_PHY_ADDRESS 0x01U
|
||||||
|
/* PHY Reset delay these values are based on a 1 ms Systick interrupt*/
|
||||||
|
#define PHY_RESET_DELAY ((uint32_t)0x000000FFU)
|
||||||
|
/* PHY Configuration delay */
|
||||||
|
#define PHY_CONFIG_DELAY ((uint32_t)0x00000FFFU)
|
||||||
|
|
||||||
|
#define PHY_READ_TO ((uint32_t)0x0000FFFFU)
|
||||||
|
#define PHY_WRITE_TO ((uint32_t)0x0000FFFFU)
|
||||||
|
|
||||||
|
/* Section 3: Common PHY Registers */
|
||||||
|
|
||||||
|
#define PHY_BCR ((uint16_t)0x0000U) /*!< Transceiver Basic Control Register */
|
||||||
|
#define PHY_BSR ((uint16_t)0x0001U) /*!< Transceiver Basic Status Register */
|
||||||
|
|
||||||
|
#define PHY_RESET ((uint16_t)0x8000U) /*!< PHY Reset */
|
||||||
|
#define PHY_LOOPBACK ((uint16_t)0x4000U) /*!< Select loop-back mode */
|
||||||
|
#define PHY_FULLDUPLEX_100M ((uint16_t)0x2100U) /*!< Set the full-duplex mode at 100 Mb/s */
|
||||||
|
#define PHY_HALFDUPLEX_100M ((uint16_t)0x2000U) /*!< Set the half-duplex mode at 100 Mb/s */
|
||||||
|
#define PHY_FULLDUPLEX_10M ((uint16_t)0x0100U) /*!< Set the full-duplex mode at 10 Mb/s */
|
||||||
|
#define PHY_HALFDUPLEX_10M ((uint16_t)0x0000U) /*!< Set the half-duplex mode at 10 Mb/s */
|
||||||
|
#define PHY_AUTONEGOTIATION ((uint16_t)0x1000U) /*!< Enable auto-negotiation function */
|
||||||
|
#define PHY_RESTART_AUTONEGOTIATION ((uint16_t)0x0200U) /*!< Restart auto-negotiation function */
|
||||||
|
#define PHY_POWERDOWN ((uint16_t)0x0800U) /*!< Select the power down mode */
|
||||||
|
#define PHY_ISOLATE ((uint16_t)0x0400U) /*!< Isolate PHY from MII */
|
||||||
|
|
||||||
|
#define PHY_AUTONEGO_COMPLETE ((uint16_t)0x0020U) /*!< Auto-Negotiation process completed */
|
||||||
|
#define PHY_LINKED_STATUS ((uint16_t)0x0004U) /*!< Valid link established */
|
||||||
|
#define PHY_JABBER_DETECTION ((uint16_t)0x0002U) /*!< Jabber condition detected */
|
||||||
|
|
||||||
|
/* Section 4: Extended PHY Registers */
|
||||||
|
#define PHY_SR ((uint16_t)0x10U) /*!< PHY status register Offset */
|
||||||
|
|
||||||
|
#define PHY_SPEED_STATUS ((uint16_t)0x0002U) /*!< PHY Speed mask */
|
||||||
|
#define PHY_DUPLEX_STATUS ((uint16_t)0x0004U) /*!< PHY Duplex mask */
|
||||||
|
|
||||||
|
/* ################## SPI peripheral configuration ########################## */
|
||||||
|
|
||||||
|
/* CRC FEATURE: Use to activate CRC feature inside HAL SPI Driver
|
||||||
|
* Activated: CRC code is present inside driver
|
||||||
|
* Deactivated: CRC code cleaned from driver
|
||||||
|
*/
|
||||||
|
|
||||||
|
#define USE_SPI_CRC 0U
|
||||||
|
|
||||||
|
/* Includes ------------------------------------------------------------------*/
|
||||||
|
/**
|
||||||
|
* @brief Include module's header file
|
||||||
|
*/
|
||||||
|
|
||||||
|
#ifdef HAL_RCC_MODULE_ENABLED
|
||||||
|
#include "stm32f7xx_hal_rcc.h"
|
||||||
|
#endif /* HAL_RCC_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_GPIO_MODULE_ENABLED
|
||||||
|
#include "stm32f7xx_hal_gpio.h"
|
||||||
|
#endif /* HAL_GPIO_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_DMA_MODULE_ENABLED
|
||||||
|
#include "stm32f7xx_hal_dma.h"
|
||||||
|
#endif /* HAL_DMA_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_CORTEX_MODULE_ENABLED
|
||||||
|
#include "stm32f7xx_hal_cortex.h"
|
||||||
|
#endif /* HAL_CORTEX_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_ADC_MODULE_ENABLED
|
||||||
|
#include "stm32f7xx_hal_adc.h"
|
||||||
|
#endif /* HAL_ADC_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_CAN_MODULE_ENABLED
|
||||||
|
#include "stm32f7xx_hal_can.h"
|
||||||
|
#endif /* HAL_CAN_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_CEC_MODULE_ENABLED
|
||||||
|
#include "stm32f7xx_hal_cec.h"
|
||||||
|
#endif /* HAL_CEC_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_CRC_MODULE_ENABLED
|
||||||
|
#include "stm32f7xx_hal_crc.h"
|
||||||
|
#endif /* HAL_CRC_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_CRYP_MODULE_ENABLED
|
||||||
|
#include "stm32f7xx_hal_cryp.h"
|
||||||
|
#endif /* HAL_CRYP_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_DMA2D_MODULE_ENABLED
|
||||||
|
#include "stm32f7xx_hal_dma2d.h"
|
||||||
|
#endif /* HAL_DMA2D_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_DAC_MODULE_ENABLED
|
||||||
|
#include "stm32f7xx_hal_dac.h"
|
||||||
|
#endif /* HAL_DAC_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_DCMI_MODULE_ENABLED
|
||||||
|
#include "stm32f7xx_hal_dcmi.h"
|
||||||
|
#endif /* HAL_DCMI_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_ETH_MODULE_ENABLED
|
||||||
|
#include "stm32f7xx_hal_eth.h"
|
||||||
|
#endif /* HAL_ETH_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_FLASH_MODULE_ENABLED
|
||||||
|
#include "stm32f7xx_hal_flash.h"
|
||||||
|
#endif /* HAL_FLASH_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_SRAM_MODULE_ENABLED
|
||||||
|
#include "stm32f7xx_hal_sram.h"
|
||||||
|
#endif /* HAL_SRAM_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_NOR_MODULE_ENABLED
|
||||||
|
#include "stm32f7xx_hal_nor.h"
|
||||||
|
#endif /* HAL_NOR_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_NAND_MODULE_ENABLED
|
||||||
|
#include "stm32f7xx_hal_nand.h"
|
||||||
|
#endif /* HAL_NAND_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_SDRAM_MODULE_ENABLED
|
||||||
|
#include "stm32f7xx_hal_sdram.h"
|
||||||
|
#endif /* HAL_SDRAM_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_HASH_MODULE_ENABLED
|
||||||
|
#include "stm32f7xx_hal_hash.h"
|
||||||
|
#endif /* HAL_HASH_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_I2C_MODULE_ENABLED
|
||||||
|
#include "stm32f7xx_hal_i2c.h"
|
||||||
|
#endif /* HAL_I2C_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_I2S_MODULE_ENABLED
|
||||||
|
#include "stm32f7xx_hal_i2s.h"
|
||||||
|
#endif /* HAL_I2S_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_IWDG_MODULE_ENABLED
|
||||||
|
#include "stm32f7xx_hal_iwdg.h"
|
||||||
|
#endif /* HAL_IWDG_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_LPTIM_MODULE_ENABLED
|
||||||
|
#include "stm32f7xx_hal_lptim.h"
|
||||||
|
#endif /* HAL_LPTIM_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_LTDC_MODULE_ENABLED
|
||||||
|
#include "stm32f7xx_hal_ltdc.h"
|
||||||
|
#endif /* HAL_LTDC_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_PWR_MODULE_ENABLED
|
||||||
|
#include "stm32f7xx_hal_pwr.h"
|
||||||
|
#endif /* HAL_PWR_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_QSPI_MODULE_ENABLED
|
||||||
|
#include "stm32f7xx_hal_qspi.h"
|
||||||
|
#endif /* HAL_QSPI_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_RNG_MODULE_ENABLED
|
||||||
|
#include "stm32f7xx_hal_rng.h"
|
||||||
|
#endif /* HAL_RNG_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_RTC_MODULE_ENABLED
|
||||||
|
#include "stm32f7xx_hal_rtc.h"
|
||||||
|
#endif /* HAL_RTC_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_SAI_MODULE_ENABLED
|
||||||
|
#include "stm32f7xx_hal_sai.h"
|
||||||
|
#endif /* HAL_SAI_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_SD_MODULE_ENABLED
|
||||||
|
#include "stm32f7xx_hal_sd.h"
|
||||||
|
#endif /* HAL_SD_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_SPDIFRX_MODULE_ENABLED
|
||||||
|
#include "stm32f7xx_hal_spdifrx.h"
|
||||||
|
#endif /* HAL_SPDIFRX_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_SPI_MODULE_ENABLED
|
||||||
|
#include "stm32f7xx_hal_spi.h"
|
||||||
|
#endif /* HAL_SPI_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_TIM_MODULE_ENABLED
|
||||||
|
#include "stm32f7xx_hal_tim.h"
|
||||||
|
#endif /* HAL_TIM_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_UART_MODULE_ENABLED
|
||||||
|
#include "stm32f7xx_hal_uart.h"
|
||||||
|
#endif /* HAL_UART_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_USART_MODULE_ENABLED
|
||||||
|
#include "stm32f7xx_hal_usart.h"
|
||||||
|
#endif /* HAL_USART_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_IRDA_MODULE_ENABLED
|
||||||
|
#include "stm32f7xx_hal_irda.h"
|
||||||
|
#endif /* HAL_IRDA_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_SMARTCARD_MODULE_ENABLED
|
||||||
|
#include "stm32f7xx_hal_smartcard.h"
|
||||||
|
#endif /* HAL_SMARTCARD_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_WWDG_MODULE_ENABLED
|
||||||
|
#include "stm32f7xx_hal_wwdg.h"
|
||||||
|
#endif /* HAL_WWDG_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_PCD_MODULE_ENABLED
|
||||||
|
#include "stm32f7xx_hal_pcd.h"
|
||||||
|
#endif /* HAL_PCD_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_HCD_MODULE_ENABLED
|
||||||
|
#include "stm32f7xx_hal_hcd.h"
|
||||||
|
#endif /* HAL_HCD_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_DFSDM_MODULE_ENABLED
|
||||||
|
#include "stm32f7xx_hal_dfsdm.h"
|
||||||
|
#endif /* HAL_DFSDM_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_DSI_MODULE_ENABLED
|
||||||
|
#include "stm32f7xx_hal_dsi.h"
|
||||||
|
#endif /* HAL_DSI_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_JPEG_MODULE_ENABLED
|
||||||
|
#include "stm32f7xx_hal_jpeg.h"
|
||||||
|
#endif /* HAL_JPEG_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_MDIOS_MODULE_ENABLED
|
||||||
|
#include "stm32f7xx_hal_mdios.h"
|
||||||
|
#endif /* HAL_MDIOS_MODULE_ENABLED */
|
||||||
|
|
||||||
|
/* Exported macro ------------------------------------------------------------*/
|
||||||
|
#ifdef USE_FULL_ASSERT
|
||||||
|
/**
|
||||||
|
* @brief The assert_param macro is used for function's parameters check.
|
||||||
|
* @param expr: If expr is false, it calls assert_failed function
|
||||||
|
* which reports the name of the source file and the source
|
||||||
|
* line number of the call that failed.
|
||||||
|
* If expr is true, it returns no value.
|
||||||
|
* @retval None
|
||||||
|
*/
|
||||||
|
#define assert_param(expr) ((expr) ? (void)0U : assert_failed((uint8_t *)__FILE__, __LINE__))
|
||||||
|
/* Exported functions ------------------------------------------------------- */
|
||||||
|
void assert_failed(uint8_t* file, uint32_t line);
|
||||||
|
#else
|
||||||
|
#define assert_param(expr) ((void)0U)
|
||||||
|
#endif /* USE_FULL_ASSERT */
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#endif /* __STM32F7xx_HAL_CONF_H */
|
||||||
|
|
||||||
|
|
||||||
|
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
|
58
src/main/target/NUCLEOF7/target.c
Normal file
58
src/main/target/NUCLEOF7/target.c
Normal file
|
@ -0,0 +1,58 @@
|
||||||
|
/*
|
||||||
|
* This file is part of Cleanflight.
|
||||||
|
*
|
||||||
|
* Cleanflight is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* Cleanflight is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*/
|
||||||
|
|
||||||
|
#include <stdint.h>
|
||||||
|
|
||||||
|
#include <platform.h>
|
||||||
|
#include "drivers/io.h"
|
||||||
|
#include "drivers/dma.h"
|
||||||
|
|
||||||
|
#include "drivers/timer.h"
|
||||||
|
|
||||||
|
#if defined(USE_DSHOT)
|
||||||
|
// DSHOT TEST
|
||||||
|
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
|
||||||
|
{ TIM12, IO_TAG(PB15), TIM_CHANNEL_2, TIM_USE_PWM | TIM_USE_PPM, 0, GPIO_AF9_TIM12, NULL, 0, 0 }, // S2_IN
|
||||||
|
{ TIM8, IO_TAG(PC6), TIM_CHANNEL_1, TIM_USE_PWM, 0, GPIO_AF3_TIM8, NULL, 0, 0 }, // S3_IN
|
||||||
|
{ TIM8, IO_TAG(PC7), TIM_CHANNEL_2, TIM_USE_PWM, 0, GPIO_AF3_TIM8, NULL, 0, 0 }, // S4_IN
|
||||||
|
{ TIM8, IO_TAG(PC9), TIM_CHANNEL_4, TIM_USE_PWM, 0, GPIO_AF3_TIM8, NULL, 0, 0 }, // S5_IN
|
||||||
|
{ TIM8, IO_TAG(PC8), TIM_CHANNEL_3, TIM_USE_PWM, 0, GPIO_AF3_TIM8, NULL, 0, 0 }, // S6_IN
|
||||||
|
|
||||||
|
{ TIM4, IO_TAG(PB8), TIM_CHANNEL_3, TIM_USE_MOTOR, 1, GPIO_AF2_TIM4, DMA1_Stream7, DMA_CHANNEL_2, DMA1_ST7_HANDLER }, // S10_OUT 1
|
||||||
|
{ TIM2, IO_TAG(PA3), TIM_CHANNEL_4, TIM_USE_MOTOR, 1, GPIO_AF1_TIM2, DMA1_Stream6, DMA_CHANNEL_3, DMA1_ST6_HANDLER }, // S1_OUT 4
|
||||||
|
{ TIM3, IO_TAG(PB5), TIM_CHANNEL_2, TIM_USE_MOTOR, 1, GPIO_AF2_TIM3, DMA1_Stream5, DMA_CHANNEL_5, DMA1_ST5_HANDLER }, // S4_OUT
|
||||||
|
{ TIM4, IO_TAG(PB9), TIM_CHANNEL_4, TIM_USE_MOTOR, 1, GPIO_AF2_TIM4, NULL, 0, 0 }, // S5_OUT 3
|
||||||
|
{ TIM9, IO_TAG(PE6), TIM_CHANNEL_2, TIM_USE_MOTOR, 1, GPIO_AF3_TIM9, NULL, 0, 0 }, // S3_OUT
|
||||||
|
{ TIM3, IO_TAG(PB4), TIM_CHANNEL_1, TIM_USE_MOTOR, 1, GPIO_AF2_TIM3, NULL, 0, 0 }, // S9_OUT
|
||||||
|
};
|
||||||
|
#else
|
||||||
|
// STANDARD LAYOUT
|
||||||
|
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
|
||||||
|
{ TIM12, IO_TAG(PB15), TIM_CHANNEL_2, TIM_USE_PWM | TIM_USE_PPM, 0, GPIO_AF9_TIM12, NULL, 0, 0 }, // S2_IN
|
||||||
|
{ TIM8, IO_TAG(PC6), TIM_CHANNEL_1, TIM_USE_PWM, 0, GPIO_AF3_TIM8, NULL, 0, 0 }, // S3_IN
|
||||||
|
{ TIM8, IO_TAG(PC7), TIM_CHANNEL_2, TIM_USE_PWM, 0, GPIO_AF3_TIM8, NULL, 0, 0 }, // S4_IN
|
||||||
|
{ TIM8, IO_TAG(PC9), TIM_CHANNEL_4, TIM_USE_PWM, 0, GPIO_AF3_TIM8, NULL, 0, 0 }, // S5_IN
|
||||||
|
{ TIM8, IO_TAG(PC8), TIM_CHANNEL_3, TIM_USE_PWM, 0, GPIO_AF3_TIM8, NULL, 0, 0 }, // S6_IN
|
||||||
|
|
||||||
|
{ TIM4, IO_TAG(PB8), TIM_CHANNEL_3, TIM_USE_MOTOR | TIM_USE_LED, 1, GPIO_AF2_TIM4, DMA1_Stream7, DMA_CHANNEL_2, DMA1_ST7_HANDLER }, // S10_OUT 1
|
||||||
|
{ TIM4, IO_TAG(PB9), TIM_CHANNEL_4, TIM_USE_MOTOR, 1, GPIO_AF2_TIM4, NULL, 0, 0 }, // S5_OUT 3
|
||||||
|
{ TIM2, IO_TAG(PA3), TIM_CHANNEL_4, TIM_USE_MOTOR, 1, GPIO_AF1_TIM2, NULL, 0, 0 }, // S1_OUT 4
|
||||||
|
{ TIM9, IO_TAG(PE6), TIM_CHANNEL_2, TIM_USE_MOTOR, 1, GPIO_AF3_TIM9, NULL, 0, 0 }, // S3_OUT
|
||||||
|
{ TIM3, IO_TAG(PB5), TIM_CHANNEL_2, TIM_USE_MOTOR, 1, GPIO_AF2_TIM3, NULL, 0, 0 }, // S4_OUT
|
||||||
|
{ TIM3, IO_TAG(PB4), TIM_CHANNEL_1, TIM_USE_MOTOR, 1, GPIO_AF2_TIM3, NULL, 0, 0 }, // S9_OUT
|
||||||
|
};
|
||||||
|
#endif
|
163
src/main/target/NUCLEOF7/target.h
Normal file
163
src/main/target/NUCLEOF7/target.h
Normal file
|
@ -0,0 +1,163 @@
|
||||||
|
/*
|
||||||
|
* This file is part of Cleanflight.
|
||||||
|
*
|
||||||
|
* Cleanflight is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* Cleanflight is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*/
|
||||||
|
|
||||||
|
#pragma once
|
||||||
|
|
||||||
|
#define TARGET_BOARD_IDENTIFIER "NUC7"
|
||||||
|
|
||||||
|
#define CONFIG_START_FLASH_ADDRESS (0x080C0000)
|
||||||
|
|
||||||
|
#define USBD_PRODUCT_STRING "NucleoF7"
|
||||||
|
|
||||||
|
//#define USE_DSHOT
|
||||||
|
//#define USE_ESC_TELEMETRY
|
||||||
|
|
||||||
|
#define LED0 PB7
|
||||||
|
#define LED1 PB14
|
||||||
|
|
||||||
|
//#define BEEPER PB2
|
||||||
|
//#define BEEPER_INVERTED
|
||||||
|
|
||||||
|
#define ACC
|
||||||
|
#define USE_FAKE_ACC
|
||||||
|
#define USE_ACC_MPU6050
|
||||||
|
#define ACC_MPU6050_ALIGN CW270_DEG
|
||||||
|
|
||||||
|
#define GYRO
|
||||||
|
#define USE_FAKE_GYRO
|
||||||
|
#define USE_GYRO_MPU6050
|
||||||
|
#define GYRO_MPU6050_ALIGN CW270_DEG
|
||||||
|
|
||||||
|
// MPU6050 interrupts
|
||||||
|
#define USE_MPU_DATA_READY_SIGNAL
|
||||||
|
#define MPU_INT_EXTI PB15
|
||||||
|
#define USE_EXTI
|
||||||
|
|
||||||
|
#define MAG
|
||||||
|
#define USE_FAKE_MAG
|
||||||
|
#define USE_MAG_HMC5883
|
||||||
|
#define MAG_HMC5883_ALIGN CW270_DEG_FLIP
|
||||||
|
|
||||||
|
#define BARO
|
||||||
|
#define USE_FAKE_BARO
|
||||||
|
#define USE_BARO_MS5611
|
||||||
|
|
||||||
|
#define USABLE_TIMER_CHANNEL_COUNT 16
|
||||||
|
|
||||||
|
#define USE_VCP
|
||||||
|
#define VBUS_SENSING_PIN PA9
|
||||||
|
|
||||||
|
//#define USE_UART1
|
||||||
|
//#define UART1_RX_PIN PA10
|
||||||
|
//#define UART1_TX_PIN PA9
|
||||||
|
|
||||||
|
#define USE_UART2
|
||||||
|
#define UART2_RX_PIN PD6
|
||||||
|
#define UART2_TX_PIN PD5
|
||||||
|
|
||||||
|
#define USE_UART3
|
||||||
|
#define UART3_RX_PIN PD9
|
||||||
|
#define UART3_TX_PIN PD8
|
||||||
|
|
||||||
|
#define USE_UART4
|
||||||
|
#define UART4_RX_PIN PC11
|
||||||
|
#define UART4_TX_PIN PC10
|
||||||
|
|
||||||
|
#define USE_UART5
|
||||||
|
#define UART5_RX_PIN PD2
|
||||||
|
#define UART5_TX_PIN PC12
|
||||||
|
|
||||||
|
#define USE_UART6
|
||||||
|
#define UART6_RX_PIN PC7
|
||||||
|
#define UART6_TX_PIN PC6
|
||||||
|
|
||||||
|
#define USE_UART7
|
||||||
|
#define UART7_RX_PIN PE7
|
||||||
|
#define UART7_TX_PIN PE8
|
||||||
|
|
||||||
|
#define USE_UART8
|
||||||
|
#define UART8_RX_PIN PE0
|
||||||
|
#define UART8_TX_PIN PE1
|
||||||
|
|
||||||
|
#define SERIAL_PORT_COUNT 8 //VCP, USART2, USART3, UART4, UART5, USART6, USART7, USART8
|
||||||
|
|
||||||
|
#define USE_SPI
|
||||||
|
#define USE_SPI_DEVICE_1
|
||||||
|
#define USE_SPI_DEVICE_4
|
||||||
|
|
||||||
|
#define SPI1_NSS_PIN PA4
|
||||||
|
#define SPI1_SCK_PIN PA5
|
||||||
|
#define SPI1_MISO_PIN PA6
|
||||||
|
#define SPI1_MOSI_PIN PA7
|
||||||
|
|
||||||
|
#define SPI4_NSS_PIN PE11
|
||||||
|
#define SPI4_SCK_PIN PE12
|
||||||
|
#define SPI4_MISO_PIN PE13
|
||||||
|
#define SPI4_MOSI_PIN PE14
|
||||||
|
|
||||||
|
#define USE_SDCARD
|
||||||
|
#define SDCARD_DETECT_INVERTED
|
||||||
|
#define SDCARD_DETECT_PIN PF14
|
||||||
|
#define SDCARD_DETECT_EXTI_LINE EXTI_Line14
|
||||||
|
#define SDCARD_DETECT_EXTI_PIN_SOURCE EXTI_PinSource14
|
||||||
|
#define SDCARD_DETECT_EXTI_PORT_SOURCE EXTI_PortSourceGPIOF
|
||||||
|
#define SDCARD_DETECT_EXTI_IRQn EXTI9_15_IRQn
|
||||||
|
|
||||||
|
#define SDCARD_SPI_INSTANCE SPI4
|
||||||
|
#define SDCARD_SPI_CS_PIN SPI4_NSS_PIN
|
||||||
|
|
||||||
|
#define SDCARD_SPI_INITIALIZATION_CLOCK_DIVIDER 256 // 422kHz
|
||||||
|
// Divide to under 25MHz for normal operation:
|
||||||
|
#define SDCARD_SPI_FULL_SPEED_CLOCK_DIVIDER 8 // 27MHz
|
||||||
|
|
||||||
|
#define SDCARD_DMA_CHANNEL_TX DMA2_Stream1
|
||||||
|
#define SDCARD_DMA_CHANNEL_TX_COMPLETE_FLAG DMA_FLAG_TCIF1_5
|
||||||
|
#define SDCARD_DMA_CLK RCC_AHB1Periph_DMA2
|
||||||
|
#define SDCARD_DMA_CHANNEL DMA_CHANNEL_4
|
||||||
|
|
||||||
|
#define USE_I2C
|
||||||
|
#define I2C_DEVICE (I2CDEV_1)
|
||||||
|
#define I2C1_SCL PB8
|
||||||
|
#define I2C1_SDA PB9
|
||||||
|
|
||||||
|
//#define I2C_DEVICE_EXT (I2CDEV_2)
|
||||||
|
|
||||||
|
#define SENSORS_SET (SENSOR_ACC|SENSOR_MAG|SENSOR_BARO)
|
||||||
|
|
||||||
|
#define USE_ADC
|
||||||
|
#define VBAT_ADC_PIN PA3
|
||||||
|
#define CURRENT_METER_ADC_PIN PC0
|
||||||
|
#define RSSI_ADC_GPIO_PIN PC3
|
||||||
|
|
||||||
|
#define LED_STRIP
|
||||||
|
|
||||||
|
#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
|
||||||
|
|
||||||
|
#define DEFAULT_FEATURES (FEATURE_BLACKBOX)
|
||||||
|
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
|
||||||
|
#define SERIALRX_PROVIDER SERIALRX_SBUS
|
||||||
|
|
||||||
|
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||||
|
|
||||||
|
#define TARGET_IO_PORTA 0xffff
|
||||||
|
#define TARGET_IO_PORTB 0xffff
|
||||||
|
#define TARGET_IO_PORTC 0xffff
|
||||||
|
#define TARGET_IO_PORTD 0xffff
|
||||||
|
#define TARGET_IO_PORTE 0xffff
|
||||||
|
#define TARGET_IO_PORTF 0xffff
|
||||||
|
|
||||||
|
#define USED_TIMERS ( TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(5) | TIM_N(12) | TIM_N(8) | TIM_N(9) | TIM_N(10) | TIM_N(11))
|
12
src/main/target/NUCLEOF7/target.mk
Normal file
12
src/main/target/NUCLEOF7/target.mk
Normal file
|
@ -0,0 +1,12 @@
|
||||||
|
F7X6XG_TARGETS += $(TARGET)
|
||||||
|
FEATURES += SDCARD VCP
|
||||||
|
|
||||||
|
TARGET_SRC = \
|
||||||
|
drivers/accgyro_fake.c \
|
||||||
|
drivers/accgyro_mpu6050.c \
|
||||||
|
drivers/barometer_fake.c \
|
||||||
|
drivers/barometer_ms5611.c \
|
||||||
|
drivers/compass_fake.c \
|
||||||
|
drivers/compass_hmc5883l.c \
|
||||||
|
drivers/light_ws2811strip.c \
|
||||||
|
drivers/light_ws2811strip_hal.c
|
|
@ -133,7 +133,8 @@
|
||||||
// Divide to under 25MHz for normal operation:
|
// Divide to under 25MHz for normal operation:
|
||||||
#define SDCARD_SPI_FULL_SPEED_CLOCK_DIVIDER 2
|
#define SDCARD_SPI_FULL_SPEED_CLOCK_DIVIDER 2
|
||||||
|
|
||||||
#define USE_ESC_TELEMETRY
|
#define USE_DSHOT
|
||||||
|
#define USE_ESC_SENSOR
|
||||||
|
|
||||||
// DSHOT output 4 uses DMA1_Channel5, so don't use it for the SDCARD until we find an alternative
|
// DSHOT output 4 uses DMA1_Channel5, so don't use it for the SDCARD until we find an alternative
|
||||||
#ifndef USE_DSHOT
|
#ifndef USE_DSHOT
|
||||||
|
@ -176,10 +177,8 @@
|
||||||
#define DEFAULT_FEATURES (FEATURE_VBAT | FEATURE_CURRENT_METER | FEATURE_BLACKBOX)
|
#define DEFAULT_FEATURES (FEATURE_VBAT | FEATURE_CURRENT_METER | FEATURE_BLACKBOX)
|
||||||
|
|
||||||
#define BUTTONS
|
#define BUTTONS
|
||||||
#define BUTTON_A_PORT GPIOB
|
#define BUTTON_A_PIN PB1
|
||||||
#define BUTTON_A_PIN Pin_1
|
#define BUTTON_B_PIN PB0
|
||||||
#define BUTTON_B_PORT GPIOB
|
|
||||||
#define BUTTON_B_PIN Pin_0
|
|
||||||
|
|
||||||
//#define AVOID_UART3_FOR_PWM_PPM // Disable this for using UART3
|
//#define AVOID_UART3_FOR_PWM_PPM // Disable this for using UART3
|
||||||
|
|
||||||
|
|
|
@ -160,7 +160,8 @@
|
||||||
#define VBAT_ADC_PIN PC2
|
#define VBAT_ADC_PIN PC2
|
||||||
//#define RSSI_ADC_PIN PA0
|
//#define RSSI_ADC_PIN PA0
|
||||||
|
|
||||||
#define USE_ESC_TELEMETRY
|
#define USE_DSHOT
|
||||||
|
#define USE_ESC_SENSOR
|
||||||
|
|
||||||
#define LED_STRIP
|
#define LED_STRIP
|
||||||
|
|
||||||
|
|
|
@ -32,10 +32,10 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
|
||||||
DEF_TIM(TIM8, CH3, PC8, TIM_USE_PWM, 0, 0), // S5_IN
|
DEF_TIM(TIM8, CH3, PC8, TIM_USE_PWM, 0, 0), // S5_IN
|
||||||
DEF_TIM(TIM8, CH4, PC9, TIM_USE_PWM, 0, 0), // S6_IN
|
DEF_TIM(TIM8, CH4, PC9, TIM_USE_PWM, 0, 0), // S6_IN
|
||||||
#ifdef REVOLT
|
#ifdef REVOLT
|
||||||
DEF_TIM(TIM2, CH3, PA2, TIM_USE_MOTOR, 1, 0), // S4_OUT D1_ST1
|
|
||||||
DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR, 1, 0), // S2_OUT D1_ST2
|
|
||||||
DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR, 1, 0), // S1_OUT D1_ST7
|
|
||||||
DEF_TIM(TIM2, CH4, PA3, TIM_USE_MOTOR, 1, 1), // S3_OUT D1_ST6
|
DEF_TIM(TIM2, CH4, PA3, TIM_USE_MOTOR, 1, 1), // S3_OUT D1_ST6
|
||||||
|
DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR, 1, 0), // S2_OUT D1_ST2
|
||||||
|
DEF_TIM(TIM2, CH3, PA2, TIM_USE_MOTOR, 1, 0), // S4_OUT D1_ST1
|
||||||
|
DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR, 1, 0), // S1_OUT D1_ST7
|
||||||
DEF_TIM(TIM4, CH1, PB6, TIM_USE_LED, 0, 0), // LED for REVOLT D1_ST0
|
DEF_TIM(TIM4, CH1, PB6, TIM_USE_LED, 0, 0), // LED for REVOLT D1_ST0
|
||||||
#else
|
#else
|
||||||
DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR, 1, 0), // S1_OUT D1_ST7
|
DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR, 1, 0), // S1_OUT D1_ST7
|
||||||
|
|
|
@ -20,43 +20,44 @@
|
||||||
#define CONFIG_START_FLASH_ADDRESS (0x08080000) //0x08080000 to 0x080A0000 (FLASH_Sector_8)
|
#define CONFIG_START_FLASH_ADDRESS (0x08080000) //0x08080000 to 0x080A0000 (FLASH_Sector_8)
|
||||||
|
|
||||||
#if defined(AIRBOTF4)
|
#if defined(AIRBOTF4)
|
||||||
#define TARGET_BOARD_IDENTIFIER "AIR4"
|
#define TARGET_BOARD_IDENTIFIER "AIR4"
|
||||||
#define USBD_PRODUCT_STRING "AirbotF4"
|
#define USBD_PRODUCT_STRING "AirbotF4"
|
||||||
|
|
||||||
#elif defined(REVOLT)
|
#elif defined(REVOLT)
|
||||||
#define TARGET_BOARD_IDENTIFIER "RVLT"
|
#define TARGET_BOARD_IDENTIFIER "RVLT"
|
||||||
#define USBD_PRODUCT_STRING "Revolt"
|
#define USBD_PRODUCT_STRING "Revolt"
|
||||||
|
|
||||||
#elif defined(SOULF4)
|
#elif defined(SOULF4)
|
||||||
#define TARGET_BOARD_IDENTIFIER "SOUL"
|
#define TARGET_BOARD_IDENTIFIER "SOUL"
|
||||||
#define USBD_PRODUCT_STRING "DemonSoulF4"
|
#define USBD_PRODUCT_STRING "DemonSoulF4"
|
||||||
|
|
||||||
#else
|
#else
|
||||||
#define TARGET_BOARD_IDENTIFIER "REVO"
|
#define TARGET_BOARD_IDENTIFIER "REVO"
|
||||||
#define USBD_PRODUCT_STRING "Revolution"
|
#define USBD_PRODUCT_STRING "Revolution"
|
||||||
|
|
||||||
#ifdef OPBL
|
#ifdef OPBL
|
||||||
#define USBD_SERIALNUMBER_STRING "0x8020000"
|
#define USBD_SERIALNUMBER_STRING "0x8020000"
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#define USE_ESC_TELEMETRY
|
#define USE_DSHOT
|
||||||
|
#define USE_ESC_SENSOR
|
||||||
|
|
||||||
#define LED0 PB5
|
#define LED0 PB5
|
||||||
// Disable LED1, conflicts with AirbotF4/Flip32F4/Revolt beeper
|
// Disable LED1, conflicts with AirbotF4/Flip32F4/Revolt beeper
|
||||||
#if defined(AIRBOTF4)
|
#if defined(AIRBOTF4)
|
||||||
#define BEEPER PB4
|
#define BEEPER PB4
|
||||||
#define BEEPER_INVERTED
|
#define BEEPER_INVERTED
|
||||||
#elif defined(REVOLT)
|
#elif defined(REVOLT)
|
||||||
#define BEEPER PB4
|
#define BEEPER PB4
|
||||||
#elif defined(SOULF4)
|
#elif defined(SOULF4)
|
||||||
#define BEEPER PB6
|
#define BEEPER PB6
|
||||||
#define BEEPER_INVERTED
|
#define BEEPER_INVERTED
|
||||||
#else
|
#else
|
||||||
#define LED1 PB4
|
#define LED1 PB4
|
||||||
// Leave beeper here but with none as io - so disabled unless mapped.
|
// Leave beeper here but with none as io - so disabled unless mapped.
|
||||||
#define BEEPER NONE
|
#define BEEPER NONE
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// PC0 used as inverter select GPIO
|
// PC0 used as inverter select GPIO
|
||||||
|
@ -70,30 +71,40 @@
|
||||||
#define MPU6500_SPI_INSTANCE SPI1
|
#define MPU6500_SPI_INSTANCE SPI1
|
||||||
|
|
||||||
#if defined(SOULF4)
|
#if defined(SOULF4)
|
||||||
#define ACC
|
#define ACC
|
||||||
#define USE_ACC_SPI_MPU6000
|
#define USE_ACC_SPI_MPU6000
|
||||||
#define GYRO_MPU6000_ALIGN CW180_DEG
|
#define GYRO_MPU6000_ALIGN CW180_DEG
|
||||||
|
|
||||||
#define GYRO
|
#define GYRO
|
||||||
#define USE_GYRO_SPI_MPU6000
|
#define USE_GYRO_SPI_MPU6000
|
||||||
#define ACC_MPU6000_ALIGN CW180_DEG
|
#define ACC_MPU6000_ALIGN CW180_DEG
|
||||||
|
|
||||||
|
#elif defined(REVOLT)
|
||||||
|
|
||||||
|
#define USE_ACC_MPU6500
|
||||||
|
#define USE_ACC_SPI_MPU6500
|
||||||
|
#define ACC_MPU6500_ALIGN CW0_DEG
|
||||||
|
|
||||||
|
#define USE_GYRO_MPU6500
|
||||||
|
#define USE_GYRO_SPI_MPU6500
|
||||||
|
#define GYRO_MPU6500_ALIGN CW0_DEG
|
||||||
|
|
||||||
#else
|
#else
|
||||||
#define ACC
|
#define ACC
|
||||||
#define USE_ACC_SPI_MPU6000
|
#define USE_ACC_SPI_MPU6000
|
||||||
#define GYRO_MPU6000_ALIGN CW270_DEG
|
#define GYRO_MPU6000_ALIGN CW270_DEG
|
||||||
|
|
||||||
#define USE_ACC_MPU6500
|
#define USE_ACC_MPU6500
|
||||||
#define USE_ACC_SPI_MPU6500
|
#define USE_ACC_SPI_MPU6500
|
||||||
#define ACC_MPU6500_ALIGN CW270_DEG
|
#define ACC_MPU6500_ALIGN CW270_DEG
|
||||||
|
|
||||||
#define GYRO
|
#define GYRO
|
||||||
#define USE_GYRO_SPI_MPU6000
|
#define USE_GYRO_SPI_MPU6000
|
||||||
#define ACC_MPU6000_ALIGN CW270_DEG
|
#define ACC_MPU6000_ALIGN CW270_DEG
|
||||||
|
|
||||||
#define USE_GYRO_MPU6500
|
#define USE_GYRO_MPU6500
|
||||||
#define USE_GYRO_SPI_MPU6500
|
#define USE_GYRO_SPI_MPU6500
|
||||||
#define GYRO_MPU6500_ALIGN CW270_DEG
|
#define GYRO_MPU6500_ALIGN CW270_DEG
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
@ -103,12 +114,12 @@
|
||||||
#define USE_MPU_DATA_READY_SIGNAL
|
#define USE_MPU_DATA_READY_SIGNAL
|
||||||
|
|
||||||
#if !defined(AIRBOTF4) && !defined(REVOLT) && !defined(SOULF4)
|
#if !defined(AIRBOTF4) && !defined(REVOLT) && !defined(SOULF4)
|
||||||
#define MAG
|
#define MAG
|
||||||
#define USE_MAG_HMC5883
|
#define USE_MAG_HMC5883
|
||||||
#define MAG_HMC5883_ALIGN CW90_DEG
|
#define MAG_HMC5883_ALIGN CW90_DEG
|
||||||
|
|
||||||
#define BARO
|
#define BARO
|
||||||
#define USE_BARO_MS5611
|
#define USE_BARO_MS5611
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
|
@ -35,7 +35,8 @@
|
||||||
#define INVERTER PC6
|
#define INVERTER PC6
|
||||||
#define INVERTER_USART USART6
|
#define INVERTER_USART USART6
|
||||||
|
|
||||||
#define USE_ESC_TELEMETRY
|
#define USE_DSHOT
|
||||||
|
#define USE_ESC_SENSOR
|
||||||
|
|
||||||
// MPU9250 interrupt
|
// MPU9250 interrupt
|
||||||
#define USE_EXTI
|
#define USE_EXTI
|
||||||
|
|
|
@ -98,6 +98,7 @@
|
||||||
#define SOFTSERIAL_2_TIMER TIM3
|
#define SOFTSERIAL_2_TIMER TIM3
|
||||||
#define SOFTSERIAL_2_TIMER_RX_HARDWARE 6 // PWM 7
|
#define SOFTSERIAL_2_TIMER_RX_HARDWARE 6 // PWM 7
|
||||||
#define SOFTSERIAL_2_TIMER_TX_HARDWARE 7 // PWM 8
|
#define SOFTSERIAL_2_TIMER_TX_HARDWARE 7 // PWM 8
|
||||||
|
#define SONAR_SOFTSERIAL2_EXCLUSIVE
|
||||||
|
|
||||||
#define USE_I2C
|
#define USE_I2C
|
||||||
#define I2C_DEVICE (I2CDEV_1) // PB6/SCL, PB7/SDA
|
#define I2C_DEVICE (I2CDEV_1) // PB6/SCL, PB7/SDA
|
||||||
|
@ -115,7 +116,8 @@
|
||||||
#define CURRENT_METER_ADC_PIN PA5
|
#define CURRENT_METER_ADC_PIN PA5
|
||||||
#define RSSI_ADC_PIN PB2
|
#define RSSI_ADC_PIN PB2
|
||||||
|
|
||||||
#define USE_ESC_TELEMETRY
|
#define USE_DSHOT
|
||||||
|
#define USE_ESC_SENSOR
|
||||||
#define REMAP_TIM17_DMA
|
#define REMAP_TIM17_DMA
|
||||||
|
|
||||||
// UART1 TX uses DMA1_Channel4, which is also used by dshot on motor 4
|
// UART1 TX uses DMA1_Channel4, which is also used by dshot on motor 4
|
||||||
|
|
|
@ -21,6 +21,8 @@
|
||||||
|
|
||||||
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT
|
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT
|
||||||
|
|
||||||
|
#define BRUSHED_ESC_AUTODETECT
|
||||||
|
|
||||||
#define LED0 PB8
|
#define LED0 PB8
|
||||||
|
|
||||||
#define BEEPER PC15
|
#define BEEPER PC15
|
||||||
|
@ -35,7 +37,8 @@
|
||||||
#define USE_MAG_DATA_READY_SIGNAL
|
#define USE_MAG_DATA_READY_SIGNAL
|
||||||
#define ENSURE_MAG_DATA_READY_IS_HIGH
|
#define ENSURE_MAG_DATA_READY_IS_HIGH
|
||||||
|
|
||||||
#define USE_ESC_TELEMETRY
|
#define USE_DSHOT
|
||||||
|
#define USE_ESC_SENSOR
|
||||||
|
|
||||||
#define GYRO
|
#define GYRO
|
||||||
#define USE_GYRO_SPI_MPU6500
|
#define USE_GYRO_SPI_MPU6500
|
||||||
|
|
|
@ -88,6 +88,7 @@
|
||||||
#define SOFTSERIAL_1_TIMER TIM2
|
#define SOFTSERIAL_1_TIMER TIM2
|
||||||
#define SOFTSERIAL_1_TIMER_RX_HARDWARE 9 // PA0 / PAD3
|
#define SOFTSERIAL_1_TIMER_RX_HARDWARE 9 // PA0 / PAD3
|
||||||
#define SOFTSERIAL_1_TIMER_TX_HARDWARE 10 // PA1 / PAD4
|
#define SOFTSERIAL_1_TIMER_TX_HARDWARE 10 // PA1 / PAD4
|
||||||
|
#define SONAR_SOFTSERIAL1_EXCLUSIVE
|
||||||
|
|
||||||
#define USE_I2C
|
#define USE_I2C
|
||||||
#define I2C_DEVICE (I2CDEV_1) // PB6/SCL, PB7/SDA
|
#define I2C_DEVICE (I2CDEV_1) // PB6/SCL, PB7/SDA
|
||||||
|
@ -129,13 +130,6 @@
|
||||||
#define RSSI_ADC_PIN PB2
|
#define RSSI_ADC_PIN PB2
|
||||||
|
|
||||||
#define LED_STRIP
|
#define LED_STRIP
|
||||||
#define WS2811_PIN PA8
|
|
||||||
#define WS2811_TIMER TIM1
|
|
||||||
#define WS2811_DMA_CHANNEL DMA1_Channel2
|
|
||||||
#define WS2811_IRQ DMA1_Channel2_IRQn
|
|
||||||
#define WS2811_DMA_TC_FLAG DMA1_FLAG_TC2
|
|
||||||
#define WS2811_DMA_HANDLER_IDENTIFER DMA1_CH2_HANDLER
|
|
||||||
#define WS2811_TIMER_GPIO_AF GPIO_AF_6
|
|
||||||
|
|
||||||
#define TRANSPONDER
|
#define TRANSPONDER
|
||||||
|
|
||||||
|
@ -147,10 +141,8 @@
|
||||||
#define DEFAULT_FEATURES FEATURE_BLACKBOX
|
#define DEFAULT_FEATURES FEATURE_BLACKBOX
|
||||||
|
|
||||||
#define BUTTONS
|
#define BUTTONS
|
||||||
#define BUTTON_A_PORT GPIOB
|
#define BUTTON_A_PIN PB1
|
||||||
#define BUTTON_A_PIN Pin_1
|
#define BUTTON_B_PIN PB0
|
||||||
#define BUTTON_B_PORT GPIOB
|
|
||||||
#define BUTTON_B_PIN Pin_0
|
|
||||||
|
|
||||||
#define SPEKTRUM_BIND
|
#define SPEKTRUM_BIND
|
||||||
// USART3,
|
// USART3,
|
||||||
|
|
|
@ -169,7 +169,8 @@
|
||||||
#define RSSI_ADC_PIN PC2
|
#define RSSI_ADC_PIN PC2
|
||||||
#define EXTERNAL1_ADC_PIN PC3
|
#define EXTERNAL1_ADC_PIN PC3
|
||||||
|
|
||||||
#define USE_ESC_TELEMETRY
|
#define USE_DSHOT
|
||||||
|
#define USE_ESC_SENSOR
|
||||||
|
|
||||||
#define LED_STRIP
|
#define LED_STRIP
|
||||||
|
|
||||||
|
|
|
@ -71,7 +71,7 @@
|
||||||
#define SOFTSERIAL_1_TIMER TIM3
|
#define SOFTSERIAL_1_TIMER TIM3
|
||||||
#define SOFTSERIAL_1_TIMER_RX_HARDWARE 4 // PWM 5
|
#define SOFTSERIAL_1_TIMER_RX_HARDWARE 4 // PWM 5
|
||||||
#define SOFTSERIAL_1_TIMER_TX_HARDWARE 5 // PWM 6
|
#define SOFTSERIAL_1_TIMER_TX_HARDWARE 5 // PWM 6
|
||||||
|
#define SONAR_SOFTSERIAL1_EXCLUSIVE
|
||||||
|
|
||||||
#define USE_I2C
|
#define USE_I2C
|
||||||
#define I2C_DEVICE (I2CDEV_1) // PB6/SCL, PB7/SDA
|
#define I2C_DEVICE (I2CDEV_1) // PB6/SCL, PB7/SDA
|
||||||
|
@ -101,7 +101,8 @@
|
||||||
#define CURRENT_METER_ADC_PIN PA5
|
#define CURRENT_METER_ADC_PIN PA5
|
||||||
#define RSSI_ADC_PIN PB2
|
#define RSSI_ADC_PIN PB2
|
||||||
|
|
||||||
#define USE_ESC_TELEMETRY
|
#define USE_DSHOT
|
||||||
|
#define USE_ESC_SENSOR
|
||||||
|
|
||||||
#define REMAP_TIM17_DMA
|
#define REMAP_TIM17_DMA
|
||||||
// UART1 TX uses DMA1_Channel4, which is also used by dshot on motor 4
|
// UART1 TX uses DMA1_Channel4, which is also used by dshot on motor 4
|
||||||
|
|
28
src/main/target/link/stm32_flash_f746.ld
Normal file
28
src/main/target/link/stm32_flash_f746.ld
Normal file
|
@ -0,0 +1,28 @@
|
||||||
|
/*
|
||||||
|
*****************************************************************************
|
||||||
|
**
|
||||||
|
** File : stm32_flash_f746.ld
|
||||||
|
**
|
||||||
|
** Abstract : Linker script for STM32F746VGTx Device with
|
||||||
|
** 1024KByte FLASH, 320KByte RAM
|
||||||
|
**
|
||||||
|
*****************************************************************************
|
||||||
|
*/
|
||||||
|
|
||||||
|
/* Entry Point */
|
||||||
|
ENTRY(Reset_Handler)
|
||||||
|
|
||||||
|
/* Specify the memory areas */
|
||||||
|
MEMORY
|
||||||
|
{
|
||||||
|
FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 768K
|
||||||
|
FLASH_CONFIG (r) : ORIGIN = 0x080C0000, LENGTH = 256K
|
||||||
|
|
||||||
|
TCM (rwx) : ORIGIN = 0x20000000, LENGTH = 64K
|
||||||
|
RAM (rwx) : ORIGIN = 0x20010000, LENGTH = 256K
|
||||||
|
MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K
|
||||||
|
}
|
||||||
|
/* note CCM could be used for stack */
|
||||||
|
REGION_ALIAS("STACKRAM", TCM)
|
||||||
|
|
||||||
|
INCLUDE "stm32_flash.ld"
|
|
@ -1,312 +0,0 @@
|
||||||
#include <stdbool.h>
|
|
||||||
#include <stdint.h>
|
|
||||||
#include <stdlib.h>
|
|
||||||
|
|
||||||
#include <platform.h>
|
|
||||||
|
|
||||||
#include "fc/config.h"
|
|
||||||
#include "config/feature.h"
|
|
||||||
#include "config/config_master.h"
|
|
||||||
|
|
||||||
#include "common/utils.h"
|
|
||||||
|
|
||||||
#include "drivers/system.h"
|
|
||||||
#include "drivers/serial.h"
|
|
||||||
#include "drivers/serial_uart.h"
|
|
||||||
#include "drivers/pwm_output.h"
|
|
||||||
|
|
||||||
#include "io/serial.h"
|
|
||||||
|
|
||||||
#include "flight/mixer.h"
|
|
||||||
|
|
||||||
#include "sensors/battery.h"
|
|
||||||
|
|
||||||
#include "esc_telemetry.h"
|
|
||||||
|
|
||||||
#include "build/debug.h"
|
|
||||||
|
|
||||||
/*
|
|
||||||
KISS ESC TELEMETRY PROTOCOL
|
|
||||||
---------------------------
|
|
||||||
|
|
||||||
One transmission will have 10 times 8-bit bytes sent with 115200 baud and 3.6V.
|
|
||||||
|
|
||||||
Byte 0: Temperature
|
|
||||||
Byte 1: Voltage high byte
|
|
||||||
Byte 2: Voltage low byte
|
|
||||||
Byte 3: Current high byte
|
|
||||||
Byte 4: Current low byte
|
|
||||||
Byte 5: Consumption high byte
|
|
||||||
Byte 6: Consumption low byte
|
|
||||||
Byte 7: Rpm high byte
|
|
||||||
Byte 8: Rpm low byte
|
|
||||||
Byte 9: 8-bit CRC
|
|
||||||
|
|
||||||
*/
|
|
||||||
|
|
||||||
/*
|
|
||||||
DEBUG INFORMATION
|
|
||||||
-----------------
|
|
||||||
|
|
||||||
set debug_mode = DEBUG_ESC_TELEMETRY in cli
|
|
||||||
|
|
||||||
0: current motor index requested
|
|
||||||
1: number of timeouts
|
|
||||||
2: voltage
|
|
||||||
3: current
|
|
||||||
*/
|
|
||||||
|
|
||||||
#ifdef USE_DSHOT
|
|
||||||
|
|
||||||
typedef struct {
|
|
||||||
bool skipped;
|
|
||||||
int16_t temperature;
|
|
||||||
int16_t voltage;
|
|
||||||
int16_t current;
|
|
||||||
int16_t consumption;
|
|
||||||
int16_t rpm;
|
|
||||||
} esc_telemetry_t;
|
|
||||||
|
|
||||||
typedef enum {
|
|
||||||
ESC_TLM_FRAME_PENDING = 1 << 0, // 1
|
|
||||||
ESC_TLM_FRAME_COMPLETE = 1 << 1 // 2
|
|
||||||
} escTlmFrameState_t;
|
|
||||||
|
|
||||||
typedef enum {
|
|
||||||
ESC_TLM_TRIGGER_WAIT = 0,
|
|
||||||
ESC_TLM_TRIGGER_READY = 1 << 0, // 1
|
|
||||||
ESC_TLM_TRIGGER_PENDING = 1 << 1 // 2
|
|
||||||
} escTlmTriggerState_t;
|
|
||||||
|
|
||||||
#define ESC_TLM_BAUDRATE 115200
|
|
||||||
#define ESC_TLM_BUFFSIZE 10
|
|
||||||
#define ESC_BOOTTIME 5000 // 5 seconds
|
|
||||||
#define ESC_REQUEST_TIMEOUT 100 // 100 ms (data transfer takes only 900us)
|
|
||||||
|
|
||||||
static bool tlmFrameDone = false;
|
|
||||||
static uint8_t tlm[ESC_TLM_BUFFSIZE] = { 0, };
|
|
||||||
static uint8_t tlmFramePosition = 0;
|
|
||||||
static serialPort_t *escTelemetryPort = NULL;
|
|
||||||
static esc_telemetry_t escTelemetryData[MAX_SUPPORTED_MOTORS];
|
|
||||||
static uint32_t escTriggerTimestamp = -1;
|
|
||||||
static uint32_t escTriggerLastTimestamp = -1;
|
|
||||||
static uint8_t timeoutRetryCount = 0;
|
|
||||||
|
|
||||||
static uint8_t escTelemetryMotor = 0; // motor index
|
|
||||||
static bool escTelemetryEnabled = false;
|
|
||||||
static escTlmTriggerState_t escTelemetryTriggerState = ESC_TLM_TRIGGER_WAIT;
|
|
||||||
|
|
||||||
static int16_t escVbat = 0;
|
|
||||||
static int16_t escCurrent = 0;
|
|
||||||
static int16_t escConsumption = 0;
|
|
||||||
|
|
||||||
static void escTelemetryDataReceive(uint16_t c);
|
|
||||||
static uint8_t update_crc8(uint8_t crc, uint8_t crc_seed);
|
|
||||||
static uint8_t get_crc8(uint8_t *Buf, uint8_t BufLen);
|
|
||||||
static void selectNextMotor(void);
|
|
||||||
|
|
||||||
bool isEscTelemetryActive(void)
|
|
||||||
{
|
|
||||||
return escTelemetryEnabled;
|
|
||||||
}
|
|
||||||
|
|
||||||
int16_t getEscTelemetryVbat(void)
|
|
||||||
{
|
|
||||||
return escVbat / 10;
|
|
||||||
}
|
|
||||||
|
|
||||||
int16_t getEscTelemetryCurrent(void)
|
|
||||||
{
|
|
||||||
return escCurrent;
|
|
||||||
}
|
|
||||||
|
|
||||||
int16_t getEscTelemetryConsumption(void)
|
|
||||||
{
|
|
||||||
return escConsumption;
|
|
||||||
}
|
|
||||||
|
|
||||||
bool escTelemetryInit(void)
|
|
||||||
{
|
|
||||||
serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_TELEMETRY_ESC);
|
|
||||||
if (!portConfig) {
|
|
||||||
return false;
|
|
||||||
}
|
|
||||||
|
|
||||||
portOptions_t options = (SERIAL_NOT_INVERTED);
|
|
||||||
|
|
||||||
// Initialize serial port
|
|
||||||
escTelemetryPort = openSerialPort(portConfig->identifier, FUNCTION_TELEMETRY_ESC, escTelemetryDataReceive, ESC_TLM_BAUDRATE, MODE_RX, options);
|
|
||||||
|
|
||||||
if (escTelemetryPort) {
|
|
||||||
escTelemetryEnabled = true;
|
|
||||||
batteryConfig()->currentMeterType = CURRENT_SENSOR_ESC;
|
|
||||||
batteryConfig()->batteryMeterType = BATTERY_SENSOR_ESC;
|
|
||||||
}
|
|
||||||
|
|
||||||
return escTelemetryPort != NULL;
|
|
||||||
}
|
|
||||||
|
|
||||||
void freeEscTelemetryPort(void)
|
|
||||||
{
|
|
||||||
closeSerialPort(escTelemetryPort);
|
|
||||||
escTelemetryPort = NULL;
|
|
||||||
escTelemetryEnabled = false;
|
|
||||||
}
|
|
||||||
|
|
||||||
// Receive ISR callback
|
|
||||||
static void escTelemetryDataReceive(uint16_t c)
|
|
||||||
{
|
|
||||||
// KISS ESC sends some data during startup, ignore this for now (maybe future use)
|
|
||||||
// startup data could be firmware version and serialnumber
|
|
||||||
|
|
||||||
if (escTelemetryTriggerState == ESC_TLM_TRIGGER_WAIT) return;
|
|
||||||
|
|
||||||
tlm[tlmFramePosition] = (uint8_t)c;
|
|
||||||
|
|
||||||
if (tlmFramePosition == ESC_TLM_BUFFSIZE - 1) {
|
|
||||||
tlmFrameDone = true;
|
|
||||||
tlmFramePosition = 0;
|
|
||||||
} else {
|
|
||||||
tlmFramePosition++;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
uint8_t escTelemetryFrameStatus(void)
|
|
||||||
{
|
|
||||||
uint8_t frameStatus = ESC_TLM_FRAME_PENDING;
|
|
||||||
uint16_t chksum, tlmsum;
|
|
||||||
|
|
||||||
if (!tlmFrameDone) {
|
|
||||||
return frameStatus;
|
|
||||||
}
|
|
||||||
|
|
||||||
tlmFrameDone = false;
|
|
||||||
|
|
||||||
// Get CRC8 checksum
|
|
||||||
chksum = get_crc8(tlm, ESC_TLM_BUFFSIZE - 1);
|
|
||||||
tlmsum = tlm[ESC_TLM_BUFFSIZE - 1]; // last byte contains CRC value
|
|
||||||
|
|
||||||
if (chksum == tlmsum) {
|
|
||||||
escTelemetryData[escTelemetryMotor].skipped = false;
|
|
||||||
escTelemetryData[escTelemetryMotor].temperature = tlm[0];
|
|
||||||
escTelemetryData[escTelemetryMotor].voltage = tlm[1] << 8 | tlm[2];
|
|
||||||
escTelemetryData[escTelemetryMotor].current = tlm[3] << 8 | tlm[4];
|
|
||||||
escTelemetryData[escTelemetryMotor].consumption = tlm[5] << 8 | tlm[6];
|
|
||||||
escTelemetryData[escTelemetryMotor].rpm = tlm[7] << 8 | tlm[8];
|
|
||||||
|
|
||||||
frameStatus = ESC_TLM_FRAME_COMPLETE;
|
|
||||||
}
|
|
||||||
|
|
||||||
return frameStatus;
|
|
||||||
}
|
|
||||||
|
|
||||||
void escTelemetryProcess(timeUs_t currentTimeUs)
|
|
||||||
{
|
|
||||||
const timeMs_t currentTimeMs = currentTimeUs / 1000;
|
|
||||||
|
|
||||||
if (!escTelemetryEnabled) {
|
|
||||||
return;
|
|
||||||
}
|
|
||||||
|
|
||||||
// Wait period of time before requesting telemetry (let the system boot first)
|
|
||||||
if (millis() < ESC_BOOTTIME) {
|
|
||||||
return;
|
|
||||||
}
|
|
||||||
else if (escTelemetryTriggerState == ESC_TLM_TRIGGER_WAIT) {
|
|
||||||
// Ready for starting requesting telemetry
|
|
||||||
escTelemetryTriggerState = ESC_TLM_TRIGGER_READY;
|
|
||||||
escTelemetryMotor = 0;
|
|
||||||
escTriggerTimestamp = currentTimeMs;
|
|
||||||
escTriggerLastTimestamp = escTriggerTimestamp;
|
|
||||||
}
|
|
||||||
else if (escTelemetryTriggerState == ESC_TLM_TRIGGER_READY) {
|
|
||||||
if (debugMode == DEBUG_ESC_TELEMETRY) debug[0] = escTelemetryMotor+1;
|
|
||||||
|
|
||||||
motorDmaOutput_t * const motor = getMotorDmaOutput(escTelemetryMotor);
|
|
||||||
motor->requestTelemetry = true;
|
|
||||||
escTelemetryTriggerState = ESC_TLM_TRIGGER_PENDING;
|
|
||||||
}
|
|
||||||
|
|
||||||
if (escTriggerTimestamp + ESC_REQUEST_TIMEOUT < currentTimeMs) {
|
|
||||||
// ESC did not repond in time, retry
|
|
||||||
timeoutRetryCount++;
|
|
||||||
escTriggerTimestamp = currentTimeMs;
|
|
||||||
escTelemetryTriggerState = ESC_TLM_TRIGGER_READY;
|
|
||||||
|
|
||||||
if (timeoutRetryCount == 4) {
|
|
||||||
// Not responding after 3 times, skip motor
|
|
||||||
escTelemetryData[escTelemetryMotor].skipped = true;
|
|
||||||
selectNextMotor();
|
|
||||||
}
|
|
||||||
|
|
||||||
if (debugMode == DEBUG_ESC_TELEMETRY) debug[1]++;
|
|
||||||
}
|
|
||||||
|
|
||||||
// Get received frame status
|
|
||||||
uint8_t state = escTelemetryFrameStatus();
|
|
||||||
|
|
||||||
if (state == ESC_TLM_FRAME_COMPLETE) {
|
|
||||||
// Wait until all ESCs are processed
|
|
||||||
if (escTelemetryMotor == getMotorCount()-1) {
|
|
||||||
escCurrent = 0;
|
|
||||||
escConsumption = 0;
|
|
||||||
escVbat = 0;
|
|
||||||
|
|
||||||
for (int i = 0; i < getMotorCount(); i++) {
|
|
||||||
if (!escTelemetryData[i].skipped) {
|
|
||||||
escVbat = i > 0 ? ((escVbat + escTelemetryData[i].voltage) / 2) : escTelemetryData[i].voltage;
|
|
||||||
escCurrent = escCurrent + escTelemetryData[i].current;
|
|
||||||
escConsumption = escConsumption + escTelemetryData[i].consumption;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
if (debugMode == DEBUG_ESC_TELEMETRY) debug[2] = escVbat;
|
|
||||||
if (debugMode == DEBUG_ESC_TELEMETRY) debug[3] = escCurrent;
|
|
||||||
|
|
||||||
selectNextMotor();
|
|
||||||
escTelemetryTriggerState = ESC_TLM_TRIGGER_READY;
|
|
||||||
}
|
|
||||||
|
|
||||||
if (escTriggerLastTimestamp + 10000 < currentTimeMs) {
|
|
||||||
// ESCs did not respond for 10 seconds
|
|
||||||
// Disable ESC telemetry and fallback to onboard vbat sensor
|
|
||||||
freeEscTelemetryPort();
|
|
||||||
escVbat = 0;
|
|
||||||
escCurrent = 0;
|
|
||||||
escConsumption = 0;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
static void selectNextMotor(void)
|
|
||||||
{
|
|
||||||
escTelemetryMotor++;
|
|
||||||
if (escTelemetryMotor == getMotorCount()) {
|
|
||||||
escTelemetryMotor = 0;
|
|
||||||
}
|
|
||||||
escTriggerTimestamp = millis();
|
|
||||||
escTriggerLastTimestamp = escTriggerTimestamp;
|
|
||||||
}
|
|
||||||
|
|
||||||
//-- CRC
|
|
||||||
|
|
||||||
static uint8_t update_crc8(uint8_t crc, uint8_t crc_seed)
|
|
||||||
{
|
|
||||||
uint8_t crc_u = crc;
|
|
||||||
crc_u ^= crc_seed;
|
|
||||||
|
|
||||||
for (int i=0; i<8; i++) {
|
|
||||||
crc_u = ( crc_u & 0x80 ) ? 0x7 ^ ( crc_u << 1 ) : ( crc_u << 1 );
|
|
||||||
}
|
|
||||||
|
|
||||||
return (crc_u);
|
|
||||||
}
|
|
||||||
|
|
||||||
static uint8_t get_crc8(uint8_t *Buf, uint8_t BufLen)
|
|
||||||
{
|
|
||||||
uint8_t crc = 0;
|
|
||||||
for(int i=0; i<BufLen; i++) crc = update_crc8(Buf[i], crc);
|
|
||||||
return (crc);
|
|
||||||
}
|
|
||||||
|
|
||||||
#endif
|
|
|
@ -1,12 +0,0 @@
|
||||||
#pragma once
|
|
||||||
|
|
||||||
#include "common/time.h"
|
|
||||||
|
|
||||||
uint8_t escTelemetryFrameStatus(void);
|
|
||||||
bool escTelemetryInit(void);
|
|
||||||
bool isEscTelemetryActive(void);
|
|
||||||
int16_t getEscTelemetryVbat(void);
|
|
||||||
int16_t getEscTelemetryCurrent(void);
|
|
||||||
int16_t getEscTelemetryConsumption(void);
|
|
||||||
|
|
||||||
void escTelemetryProcess(timeUs_t currentTimeUs);
|
|
|
@ -529,7 +529,7 @@ void handleFrSkyTelemetry(rxConfig_t *rxConfig, uint16_t deadband3d_throttle)
|
||||||
sendTemperature1();
|
sendTemperature1();
|
||||||
sendThrottleOrBatterySizeAsRpm(rxConfig, deadband3d_throttle);
|
sendThrottleOrBatterySizeAsRpm(rxConfig, deadband3d_throttle);
|
||||||
|
|
||||||
if ((feature(FEATURE_VBAT) || feature(FEATURE_ESC_TELEMETRY)) && batteryCellCount > 0) {
|
if ((feature(FEATURE_VBAT) || feature(FEATURE_ESC_SENSOR)) && batteryCellCount > 0) {
|
||||||
sendVoltage();
|
sendVoltage();
|
||||||
sendVoltageAmp();
|
sendVoltageAmp();
|
||||||
sendAmperage();
|
sendAmperage();
|
||||||
|
|
|
@ -646,7 +646,7 @@ void handleSmartPortTelemetry(void)
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
case FSSP_DATAID_CURRENT :
|
case FSSP_DATAID_CURRENT :
|
||||||
if (feature(FEATURE_CURRENT_METER) || feature(FEATURE_ESC_TELEMETRY)) {
|
if (feature(FEATURE_CURRENT_METER) || feature(FEATURE_ESC_SENSOR)) {
|
||||||
smartPortSendPackage(id, amperage / 10); // given in 10mA steps, unknown requested unit
|
smartPortSendPackage(id, amperage / 10); // given in 10mA steps, unknown requested unit
|
||||||
smartPortHasRequest = 0;
|
smartPortHasRequest = 0;
|
||||||
}
|
}
|
||||||
|
@ -659,7 +659,7 @@ void handleSmartPortTelemetry(void)
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
case FSSP_DATAID_FUEL :
|
case FSSP_DATAID_FUEL :
|
||||||
if (feature(FEATURE_CURRENT_METER) || feature(FEATURE_ESC_TELEMETRY)) {
|
if (feature(FEATURE_CURRENT_METER) || feature(FEATURE_ESC_SENSOR)) {
|
||||||
smartPortSendPackage(id, mAhDrawn); // given in mAh, unknown requested unit
|
smartPortSendPackage(id, mAhDrawn); // given in mAh, unknown requested unit
|
||||||
smartPortHasRequest = 0;
|
smartPortHasRequest = 0;
|
||||||
}
|
}
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue