Skip to content

Commit

Permalink
Merge pull request #2958 from iNavFlight/de_gyro_sync_rework
Browse files Browse the repository at this point in the history
Deprecate gyro sync
  • Loading branch information
digitalentity authored Mar 23, 2018
2 parents 68a0751 + 6ce5940 commit c60386f
Show file tree
Hide file tree
Showing 78 changed files with 884 additions and 305 deletions.
24 changes: 18 additions & 6 deletions Makefile
Original file line number Diff line number Diff line change
Expand Up @@ -104,7 +104,7 @@ endif
# silently ignore if the file is not present. Allows for target specific.
-include $(ROOT)/src/main/target/$(BASE_TARGET)/target.mk

F4_TARGETS = $(F405_TARGETS) $(F411_TARGETS) $(F427_TARGETS)
F4_TARGETS = $(F405_TARGETS) $(F411_TARGETS) $(F427_TARGETS) $(F446_TARGETS)
F7_TARGETS = $(F7X2RE_TARGETS) $(F7X5XE_TARGETS) $(F7X5XG_TARGETS) $(F7X5XI_TARGETS) $(F7X6XG_TARGETS)

ifeq ($(filter $(TARGET),$(VALID_TARGETS)),)
Expand All @@ -117,7 +117,7 @@ endif

128K_TARGETS = $(F1_TARGETS)
256K_TARGETS = $(F3_TARGETS)
512K_TARGETS = $(F411_TARGETS) $(F7X2RE_TARGETS) $(F7X5XE_TARGETS)
512K_TARGETS = $(F411_TARGETS) $(F446_TARGETS) $(F7X2RE_TARGETS) $(F7X5XE_TARGETS)
1024K_TARGETS = $(F405_TARGETS) $(F7X5XG_TARGETS) $(F7X6XG_TARGETS)
2048K_TARGETS = $(F427_TARGETS) $(F7X5XI_TARGETS)

Expand Down Expand Up @@ -253,6 +253,10 @@ ifeq ($(TARGET),$(filter $(TARGET), $(F427_TARGETS)))
EXCLUDES += stm32f4xx_fsmc.c
endif

ifeq ($(TARGET),$(filter $(TARGET), $(F446_TARGETS)))
EXCLUDES += stm32f4xx_fsmc.c
endif

STDPERIPH_SRC := $(filter-out ${EXCLUDES}, $(STDPERIPH_SRC))

#USB
Expand Down Expand Up @@ -309,13 +313,18 @@ else ifeq ($(TARGET),$(filter $(TARGET),$(F405_TARGETS)))
DEVICE_FLAGS = -DSTM32F40_41xxx
LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f405.ld
STARTUP_SRC = startup_stm32f40xx.s
else ifeq ($(TARGET),$(filter $(TARGET),$(F446_TARGETS)))
DEVICE_FLAGS = -DSTM32F446xx
LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f446.ld
STARTUP_SRC = startup_stm32f446xx.s
else ifeq ($(TARGET),$(filter $(TARGET),$(F427_TARGETS)))
DEVICE_FLAGS = -DSTM32F427_437xx
LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f427.ld
STARTUP_SRC = startup_stm32f427xx.s
else
$(error Unknown MCU for F4 target)
endif

DEVICE_FLAGS += -DHSE_VALUE=$(HSE_VALUE)

TARGET_FLAGS = -D$(TARGET)
Expand Down Expand Up @@ -575,7 +584,6 @@ COMMON_SRC = \
drivers/display.c \
drivers/exti.c \
drivers/gps_i2cnav.c \
drivers/gyro_sync.c \
drivers/io.c \
drivers/io_pca9685.c \
drivers/light_led.c \
Expand Down Expand Up @@ -758,6 +766,7 @@ endif

STM32F10x_COMMON_SRC = \
startup_stm32f10x_md_gcc.S \
drivers/accgyro/accgyro.c \
drivers/adc_stm32f10x.c \
drivers/bus_i2c_stm32f10x.c \
drivers/dma.c \
Expand All @@ -771,6 +780,7 @@ STM32F10x_COMMON_SRC = \
STM32F30x_COMMON_SRC = \
startup_stm32f30x_md_gcc.S \
target/system_stm32f30x.c \
drivers/accgyro/accgyro.c \
drivers/adc_stm32f30x.c \
drivers/bus_i2c_stm32f30x.c \
drivers/dma.c \
Expand All @@ -781,6 +791,7 @@ STM32F30x_COMMON_SRC = \

STM32F4xx_COMMON_SRC = \
target/system_stm32f4xx.c \
drivers/accgyro/accgyro.c \
drivers/accgyro/accgyro_mpu.c \
drivers/adc_stm32f4xx.c \
drivers/adc_stm32f4xx.c \
Expand All @@ -795,6 +806,7 @@ STM32F4xx_COMMON_SRC = \

STM32F7xx_COMMON_SRC = \
target/system_stm32f7xx.c \
drivers/accgyro/accgyro.c \
drivers/accgyro/accgyro_mpu.c \
drivers/adc_stm32f7xx.c \
drivers/bus_i2c_hal.c \
Expand Down Expand Up @@ -1034,7 +1046,7 @@ targets-group-rest: $(GROUP_OTHER_TARGETS)
$(VALID_TARGETS):
$(V0) echo "" && \
echo "Building $@" && \
$(MAKE) -j 4 TARGET=$@ && \
$(MAKE) -j 8 TARGET=$@ && \
echo "Building $@ succeeded."

## clean : clean up all temporary / machine-generated files
Expand All @@ -1051,11 +1063,11 @@ clean_test:

## clean_<TARGET> : clean up one specific target
$(CLEAN_TARGETS) :
$(V0) $(MAKE) -j 4 TARGET=$(subst clean_,,$@) clean
$(V0) $(MAKE) -j 8 TARGET=$(subst clean_,,$@) clean

## <TARGET>_clean : clean up one specific target (alias for above)
$(TARGETS_CLEAN) :
$(V0) $(MAKE) -j 4 TARGET=$(subst _clean,,$@) clean
$(V0) $(MAKE) -j 8 TARGET=$(subst _clean,,$@) clean

## clean_all : clean all valid targets
clean_all:$(CLEAN_TARGETS)
Expand Down
1 change: 0 additions & 1 deletion src/main/blackbox/blackbox.c
Original file line number Diff line number Diff line change
Expand Up @@ -1381,7 +1381,6 @@ static bool blackboxWriteSysinfo(void)
);

BLACKBOX_PRINT_HEADER_LINE("looptime", "%d", getPidUpdateRate());
BLACKBOX_PRINT_HEADER_LINE("gyro_sync_denom", "%d", gyroConfig()->gyroSyncDenominator);
BLACKBOX_PRINT_HEADER_LINE("rc_rate", "%d", 100); //For compatibility reasons write rc_rate 100
BLACKBOX_PRINT_HEADER_LINE("rc_expo", "%d", currentControlRateProfile->stabilized.rcExpo8);
BLACKBOX_PRINT_HEADER_LINE("rc_yaw_expo", "%d", currentControlRateProfile->stabilized.rcYawExpo8);
Expand Down
1 change: 0 additions & 1 deletion src/main/cms/cms_menu_imu.c
Original file line number Diff line number Diff line change
Expand Up @@ -423,7 +423,6 @@ static const OSD_Entry cmsx_menuGyroEntries[] =
OSD_LABEL_DATA_ENTRY("-- GYRO GLB --", profileIndexString),

OSD_SETTING_ENTRY("GYRO SYNC", SETTING_GYRO_SYNC),
OSD_SETTING_ENTRY("GYRO DENOM", SETTING_GYRO_SYNC_DENOM),
OSD_SETTING_ENTRY("GYRO LPF", SETTING_GYRO_HARDWARE_LPF),

OSD_BACK_ENTRY,
Expand Down
8 changes: 5 additions & 3 deletions src/main/config/config_streamer.c
Original file line number Diff line number Diff line change
Expand Up @@ -37,11 +37,13 @@ extern uint8_t __config_end;
# define FLASH_PAGE_SIZE (0x800)
// F4
# elif defined(STM32F40_41xxx)
# define FLASH_PAGE_SIZE ((uint32_t)0x20000)
# define FLASH_PAGE_SIZE ((uint32_t)0x4000)
# elif defined (STM32F411xE)
# define FLASH_PAGE_SIZE ((uint32_t)0x20000)
# define FLASH_PAGE_SIZE ((uint32_t)0x4000)
# elif defined(STM32F446xx)
# define FLASH_PAGE_SIZE ((uint32_t)0x4000)
# elif defined(STM32F427_437xx)
# define FLASH_PAGE_SIZE ((uint32_t)0x20000) // 128K sectors
# define FLASH_PAGE_SIZE ((uint32_t)0x4000)
// F7
#elif defined(STM32F722xx)
# define FLASH_PAGE_SIZE ((uint32_t)0x4000) // 16K sectors
Expand Down
127 changes: 127 additions & 0 deletions src/main/drivers/accgyro/accgyro.c
Original file line number Diff line number Diff line change
@@ -0,0 +1,127 @@
/*
* 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 <stdlib.h>
#include <string.h>

#include "platform.h"

#include "build/atomic.h"
#include "build/build_config.h"
#include "build/debug.h"

#include "common/maths.h"
#include "common/utils.h"

#include "drivers/bus.h"
#include "drivers/exti.h"
#include "drivers/io.h"
#include "drivers/exti.h"
#include "drivers/nvic.h"
#include "drivers/sensor.h"
#include "drivers/system.h"
#include "drivers/time.h"

#include "drivers/sensor.h"
#include "drivers/accgyro/accgyro.h"

const gyroFilterAndRateConfig_t * chooseGyroConfig(uint8_t desiredLpf, uint16_t desiredRateHz, const gyroFilterAndRateConfig_t * configs, int count)
{
int i;
int8_t selectedLpf = configs[0].gyroLpf;
const gyroFilterAndRateConfig_t * candidate = &configs[0];

// Choose closest supported LPF value
for (i = 1; i < count; i++) {
if (ABS(desiredLpf - configs[i].gyroLpf) < ABS(desiredLpf - selectedLpf)) {
selectedLpf = configs[i].gyroLpf;
candidate = &configs[i];
}
}

// Now find the closest update rate
for (i = 0; i < count; i++) {
if ((configs[i].gyroLpf == selectedLpf) && (ABS(desiredRateHz - candidate->gyroRateHz) > ABS(desiredRateHz - configs[i].gyroRateHz))) {
candidate = &configs[i];
}
}

DEBUG_TRACE("GYRO CONFIG { %d, %d } -> { %d, %d}; regs 0x%02X, 0x%02X",
desiredLpf, desiredRateHz,
candidate->gyroLpf, candidate->gyroRateHz,
candidate->gyroConfigValues[0], candidate->gyroConfigValues[1]);

return candidate;
}

/*
* Gyro interrupt service routine
*/
#if defined(USE_MPU_DATA_READY_SIGNAL) && defined(USE_EXTI)
static void gyroIntExtiHandler(extiCallbackRec_t *cb)
{
gyroDev_t *gyro = container_of(cb, gyroDev_t, exti);
gyro->dataReady = true;
if (gyro->updateFn) {
gyro->updateFn(gyro);
}
}
#endif

void gyroIntExtiInit(gyroDev_t *gyro)
{
if (!gyro->busDev->irqPin) {
return;
}

#if defined(USE_MPU_DATA_READY_SIGNAL) && defined(USE_EXTI)
#ifdef ENSURE_MPU_DATA_READY_IS_LOW
uint8_t status = IORead(gyro->busDev->irqPin);
if (status) {
return;
}
#endif

#if defined (STM32F7)
IOInit(gyro->busDev->irqPin, OWNER_MPU, RESOURCE_EXTI, 0);

EXTIHandlerInit(&gyro->exti, gyroIntExtiHandler);
EXTIConfig(gyro->busDev->irqPin, &gyro->exti, NVIC_PRIO_GYRO_INT_EXTI, IO_CONFIG(GPIO_MODE_INPUT,0,GPIO_NOPULL)); // TODO - maybe pullup / pulldown ?
#else
IOInit(gyro->busDev->irqPin, OWNER_MPU, RESOURCE_EXTI, 0);
IOConfigGPIO(gyro->busDev->irqPin, IOCFG_IN_FLOATING);

EXTIHandlerInit(&gyro->exti, gyroIntExtiHandler);
EXTIConfig(gyro->busDev->irqPin, &gyro->exti, NVIC_PRIO_GYRO_INT_EXTI, EXTI_Trigger_Rising);
EXTIEnable(gyro->busDev->irqPin, true);
#endif
#endif
}

bool gyroCheckDataReady(gyroDev_t* gyro)
{
bool ret;
if (gyro->dataReady) {
ret = true;
gyro->dataReady = false;
} else {
ret = false;
}
return ret;
}
21 changes: 12 additions & 9 deletions src/main/drivers/accgyro/accgyro.h
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,6 @@
#include "common/axis.h"
#include "drivers/exti.h"
#include "drivers/sensor.h"
#include "drivers/accgyro/accgyro_mpu.h"

#define GYRO_LPF_256HZ 0
#define GYRO_LPF_188HZ 1
Expand All @@ -32,11 +31,11 @@
#define GYRO_LPF_5HZ 6
#define GYRO_LPF_NONE 7

typedef enum {
GYRO_RATE_1_kHz,
GYRO_RATE_8_kHz,
GYRO_RATE_32_kHz,
} gyroRateKHz_e;
typedef struct {
uint8_t gyroLpf;
uint16_t gyroRateHz;
uint8_t gyroConfigValues[2];
} gyroFilterAndRateConfig_t;

typedef struct gyroDev_s {
busDevice_t * busDev;
Expand All @@ -49,11 +48,11 @@ typedef struct gyroDev_s {
float scale; // scalefactor
int16_t gyroADCRaw[XYZ_AXIS_COUNT];
int16_t gyroZero[XYZ_AXIS_COUNT];
uint8_t lpf;
uint8_t imuSensorToUse;
gyroRateKHz_e gyroRateKHz;
uint8_t mpuDividerDrops;
uint8_t lpf; // Configuration value: Hardware LPF setting
uint32_t requestedSampleIntervalUs; // Requested sample interval
volatile bool dataReady;
uint32_t sampleRateIntervalUs; // Gyro driver should set this to actual sampling rate as signaled by IRQ
sensor_align_e gyroAlign;
} gyroDev_t;

Expand All @@ -66,3 +65,7 @@ typedef struct accDev_s {
uint8_t imuSensorToUse;
sensor_align_e accAlign;
} accDev_t;

const gyroFilterAndRateConfig_t * chooseGyroConfig(uint8_t desiredLpf, uint16_t desiredRateHz, const gyroFilterAndRateConfig_t * configs, int count);
void gyroIntExtiInit(struct gyroDev_s *gyro);
bool gyroCheckDataReady(struct gyroDev_s *gyro);
Loading

0 comments on commit c60386f

Please sign in to comment.