Moved 'rpm_filter' into 'flight'.
This commit is contained in:
parent
52a46255e8
commit
5141bbfa94
|
@ -83,10 +83,12 @@ COMMON_SRC = \
|
|||
flight/position.c \
|
||||
flight/failsafe.c \
|
||||
flight/gps_rescue.c \
|
||||
flight/gyroanalyse.c \
|
||||
flight/imu.c \
|
||||
flight/mixer.c \
|
||||
flight/mixer_tricopter.c \
|
||||
flight/pid.c \
|
||||
flight/rpm_filter.c \
|
||||
flight/servos.c \
|
||||
flight/servos_tricopter.c \
|
||||
io/serial_4way.c \
|
||||
|
@ -113,8 +115,6 @@ COMMON_SRC = \
|
|||
sensors/boardalignment.c \
|
||||
sensors/compass.c \
|
||||
sensors/gyro.c \
|
||||
sensors/gyroanalyse.c \
|
||||
sensors/rpm_filter.c \
|
||||
sensors/initialisation.c \
|
||||
blackbox/blackbox.c \
|
||||
blackbox/blackbox_encoding.c \
|
||||
|
@ -228,9 +228,11 @@ SPEED_OPTIMISED_SRC := $(SPEED_OPTIMISED_SRC) \
|
|||
fc/rc.c \
|
||||
fc/rc_controls.c \
|
||||
fc/runtime_config.c \
|
||||
flight/gyroanalyse.c \
|
||||
flight/imu.c \
|
||||
flight/mixer.c \
|
||||
flight/pid.c \
|
||||
flight/rpm_filter.c \
|
||||
rx/ibus.c \
|
||||
rx/rx.c \
|
||||
rx/rx_spi.c \
|
||||
|
@ -245,8 +247,6 @@ SPEED_OPTIMISED_SRC := $(SPEED_OPTIMISED_SRC) \
|
|||
sensors/acceleration.c \
|
||||
sensors/boardalignment.c \
|
||||
sensors/gyro.c \
|
||||
sensors/gyroanalyse.c \
|
||||
sensors/rpm_filter.c \
|
||||
$(CMSIS_SRC) \
|
||||
$(DEVICE_STDPERIPH_SRC) \
|
||||
|
||||
|
|
|
@ -52,6 +52,7 @@
|
|||
#include "flight/mixer.h"
|
||||
#include "flight/pid.h"
|
||||
#include "flight/position.h"
|
||||
#include "flight/rpm_filter.h"
|
||||
#include "flight/servos.h"
|
||||
|
||||
#include "io/beeper.h"
|
||||
|
@ -105,7 +106,6 @@
|
|||
#include "sensors/esc_sensor.h"
|
||||
#include "sensors/gyro.h"
|
||||
#include "sensors/rangefinder.h"
|
||||
#include "sensors/rpm_filter.h"
|
||||
|
||||
#include "telemetry/frsky_hub.h"
|
||||
#include "telemetry/ibus_shared.h"
|
||||
|
|
|
@ -45,29 +45,29 @@
|
|||
#include "flight/imu.h"
|
||||
#include "flight/mixer.h"
|
||||
#include "flight/pid.h"
|
||||
#include "flight/rpm_filter.h"
|
||||
#include "flight/servos.h"
|
||||
|
||||
#include "io/beeper.h"
|
||||
#include "io/gps.h"
|
||||
#include "io/ledstrip.h"
|
||||
#include "io/serial.h"
|
||||
#include "io/gps.h"
|
||||
|
||||
#include "osd/osd.h"
|
||||
|
||||
#include "pg/beeper.h"
|
||||
#include "pg/beeper_dev.h"
|
||||
#include "pg/rx.h"
|
||||
#include "pg/pg.h"
|
||||
#include "pg/pg_ids.h"
|
||||
#include "pg/rx.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
|
||||
#include "scheduler/scheduler.h"
|
||||
|
||||
#include "sensors/acceleration.h"
|
||||
#include "sensors/battery.h"
|
||||
#include "sensors/gyro.h"
|
||||
#include "sensors/rpm_filter.h"
|
||||
|
||||
#include "scheduler/scheduler.h"
|
||||
|
||||
static bool configIsDirty; /* someone indicated that the config is modified and it is not yet saved */
|
||||
|
||||
|
|
|
@ -37,9 +37,6 @@
|
|||
#include "common/utils.h"
|
||||
|
||||
#include "config/feature.h"
|
||||
#include "pg/pg.h"
|
||||
#include "pg/pg_ids.h"
|
||||
#include "pg/rx.h"
|
||||
|
||||
#include "drivers/light_led.h"
|
||||
#include "drivers/sound_beeper.h"
|
||||
|
@ -47,17 +44,6 @@
|
|||
#include "drivers/time.h"
|
||||
#include "drivers/transponder_ir.h"
|
||||
|
||||
#include "sensors/acceleration.h"
|
||||
#include "sensors/barometer.h"
|
||||
#include "sensors/battery.h"
|
||||
#include "sensors/boardalignment.h"
|
||||
#include "sensors/gyro.h"
|
||||
#include "sensors/sensors.h"
|
||||
#if defined(USE_GYRO_DATA_ANALYSE)
|
||||
#include "sensors/gyroanalyse.h"
|
||||
#endif
|
||||
#include "sensors/rpm_filter.h"
|
||||
|
||||
#include "fc/config.h"
|
||||
#include "fc/controlrate_profile.h"
|
||||
#include "fc/core.h"
|
||||
|
@ -67,37 +53,50 @@
|
|||
#include "fc/runtime_config.h"
|
||||
#include "fc/stats.h"
|
||||
|
||||
#include "msp/msp_serial.h"
|
||||
#include "flight/failsafe.h"
|
||||
#include "flight/gps_rescue.h"
|
||||
#if defined(USE_GYRO_DATA_ANALYSE)
|
||||
#include "flight/gyroanalyse.h"
|
||||
#endif
|
||||
#include "flight/imu.h"
|
||||
#include "flight/mixer.h"
|
||||
#include "flight/pid.h"
|
||||
#include "flight/position.h"
|
||||
#include "flight/rpm_filter.h"
|
||||
#include "flight/servos.h"
|
||||
|
||||
#include "io/beeper.h"
|
||||
#include "io/gps.h"
|
||||
#include "io/motors.h"
|
||||
#include "io/pidaudio.h"
|
||||
#include "io/servos.h"
|
||||
#include "io/serial.h"
|
||||
#include "io/servos.h"
|
||||
#include "io/statusindicator.h"
|
||||
#include "io/transponder_ir.h"
|
||||
#include "io/vtx_control.h"
|
||||
#include "io/vtx_rtc6705.h"
|
||||
|
||||
#include "msp/msp_serial.h"
|
||||
|
||||
#include "osd/osd.h"
|
||||
|
||||
#include "pg/pg.h"
|
||||
#include "pg/pg_ids.h"
|
||||
#include "pg/rx.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
|
||||
#include "scheduler/scheduler.h"
|
||||
|
||||
#include "sensors/acceleration.h"
|
||||
#include "sensors/barometer.h"
|
||||
#include "sensors/battery.h"
|
||||
#include "sensors/boardalignment.h"
|
||||
#include "sensors/gyro.h"
|
||||
#include "sensors/sensors.h"
|
||||
|
||||
#include "telemetry/telemetry.h"
|
||||
|
||||
#include "flight/position.h"
|
||||
#include "flight/failsafe.h"
|
||||
#include "flight/imu.h"
|
||||
#include "flight/mixer.h"
|
||||
#include "flight/pid.h"
|
||||
#include "flight/servos.h"
|
||||
#include "flight/gps_rescue.h"
|
||||
|
||||
|
||||
// June 2013 V2.2-dev
|
||||
|
||||
enum {
|
||||
ALIGN_GYRO = 0,
|
||||
|
|
|
@ -27,8 +27,14 @@
|
|||
|
||||
#include "blackbox/blackbox.h"
|
||||
|
||||
#include "build/build_config.h"
|
||||
#include "build/debug.h"
|
||||
|
||||
#include "cli/cli.h"
|
||||
|
||||
#include "cms/cms.h"
|
||||
#include "cms/cms_types.h"
|
||||
|
||||
#include "common/axis.h"
|
||||
#include "common/color.h"
|
||||
#include "common/maths.h"
|
||||
|
@ -37,14 +43,7 @@
|
|||
#include "config/config_eeprom.h"
|
||||
#include "config/feature.h"
|
||||
|
||||
#include "cms/cms.h"
|
||||
#include "cms/cms_types.h"
|
||||
|
||||
#include "drivers/accgyro/accgyro.h"
|
||||
#include "drivers/camera_control.h"
|
||||
#include "drivers/compass/compass.h"
|
||||
#include "drivers/pwm_esc_detect.h"
|
||||
#include "drivers/pwm_output.h"
|
||||
#include "drivers/adc.h"
|
||||
#include "drivers/bus.h"
|
||||
#include "drivers/bus_i2c.h"
|
||||
|
@ -74,22 +73,51 @@
|
|||
#include "drivers/time.h"
|
||||
#include "drivers/timer.h"
|
||||
#include "drivers/transponder_ir.h"
|
||||
#include "drivers/exti.h"
|
||||
#include "drivers/usb_io.h"
|
||||
#include "drivers/vtx_rtc6705.h"
|
||||
#include "drivers/vtx_common.h"
|
||||
#include "drivers/vtx_table.h"
|
||||
#ifdef USE_USB_MSC
|
||||
#include "drivers/usb_msc.h"
|
||||
#endif
|
||||
#include "drivers/vtx_common.h"
|
||||
#include "drivers/vtx_rtc6705.h"
|
||||
#include "drivers/vtx_table.h"
|
||||
|
||||
#include "fc/board_info.h"
|
||||
#include "fc/config.h"
|
||||
#include "fc/dispatch.h"
|
||||
#include "fc/init.h"
|
||||
#include "fc/tasks.h"
|
||||
#include "fc/rc_controls.h"
|
||||
#include "fc/runtime_config.h"
|
||||
#include "fc/dispatch.h"
|
||||
#include "fc/tasks.h"
|
||||
|
||||
#include "flight/failsafe.h"
|
||||
#include "flight/imu.h"
|
||||
#include "flight/mixer.h"
|
||||
#include "flight/pid.h"
|
||||
#include "flight/rpm_filter.h"
|
||||
#include "flight/servos.h"
|
||||
|
||||
#include "io/asyncfatfs/asyncfatfs.h"
|
||||
#include "io/beeper.h"
|
||||
#include "io/dashboard.h"
|
||||
#include "io/displayport_max7456.h"
|
||||
#include "io/displayport_msp.h"
|
||||
#include "io/displayport_srxl.h"
|
||||
#include "io/flashfs.h"
|
||||
#include "io/gimbal.h"
|
||||
#include "io/gps.h"
|
||||
#include "io/ledstrip.h"
|
||||
#include "io/motors.h"
|
||||
#include "io/pidaudio.h"
|
||||
#include "io/piniobox.h"
|
||||
#include "io/rcdevice_cam.h"
|
||||
#include "io/serial.h"
|
||||
#include "io/servos.h"
|
||||
#include "io/transponder_ir.h"
|
||||
#include "io/vtx.h"
|
||||
#include "io/vtx_control.h"
|
||||
#include "io/vtx_rtc6705.h"
|
||||
#include "io/vtx_smartaudio.h"
|
||||
#include "io/vtx_tramp.h"
|
||||
|
||||
#ifdef USE_PERSISTENT_MSC_RTC
|
||||
#include "msc/usbd_storage.h"
|
||||
|
@ -98,6 +126,8 @@
|
|||
#include "msp/msp.h"
|
||||
#include "msp/msp_serial.h"
|
||||
|
||||
#include "osd/osd.h"
|
||||
|
||||
#include "pg/adc.h"
|
||||
#include "pg/beeper.h"
|
||||
#include "pg/beeper_dev.h"
|
||||
|
@ -118,30 +148,6 @@
|
|||
#include "rx/rx_spi.h"
|
||||
#include "rx/spektrum.h"
|
||||
|
||||
#include "io/beeper.h"
|
||||
#include "io/displayport_max7456.h"
|
||||
#include "io/displayport_srxl.h"
|
||||
#include "io/serial.h"
|
||||
#include "io/flashfs.h"
|
||||
#include "io/gps.h"
|
||||
#include "io/motors.h"
|
||||
#include "io/servos.h"
|
||||
#include "io/gimbal.h"
|
||||
#include "io/ledstrip.h"
|
||||
#include "io/dashboard.h"
|
||||
#include "io/asyncfatfs/asyncfatfs.h"
|
||||
#include "io/transponder_ir.h"
|
||||
#include "io/pidaudio.h"
|
||||
#include "io/piniobox.h"
|
||||
#include "io/displayport_msp.h"
|
||||
#include "io/vtx.h"
|
||||
#include "io/vtx_rtc6705.h"
|
||||
#include "io/vtx_control.h"
|
||||
#include "io/vtx_smartaudio.h"
|
||||
#include "io/vtx_tramp.h"
|
||||
|
||||
#include "osd/osd.h"
|
||||
|
||||
#include "scheduler/scheduler.h"
|
||||
|
||||
#include "sensors/acceleration.h"
|
||||
|
@ -152,26 +158,14 @@
|
|||
#include "sensors/esc_sensor.h"
|
||||
#include "sensors/gyro.h"
|
||||
#include "sensors/initialisation.h"
|
||||
#include "sensors/rpm_filter.h"
|
||||
#include "sensors/sensors.h"
|
||||
|
||||
#include "telemetry/telemetry.h"
|
||||
|
||||
#include "flight/failsafe.h"
|
||||
#include "flight/imu.h"
|
||||
#include "flight/mixer.h"
|
||||
#include "flight/pid.h"
|
||||
#include "flight/servos.h"
|
||||
|
||||
#include "io/rcdevice_cam.h"
|
||||
|
||||
#ifdef USE_HARDWARE_REVISION_DETECTION
|
||||
#include "hardware_revision.h"
|
||||
#endif
|
||||
|
||||
#include "build/build_config.h"
|
||||
#include "build/debug.h"
|
||||
|
||||
#ifdef TARGET_PREINIT
|
||||
void targetPreInit(void);
|
||||
#endif
|
||||
|
|
|
@ -39,10 +39,11 @@
|
|||
#include "drivers/time.h"
|
||||
|
||||
#include "sensors/gyro.h"
|
||||
#include "sensors/gyroanalyse.h"
|
||||
|
||||
#include "fc/core.h"
|
||||
|
||||
#include "gyroanalyse.h"
|
||||
|
||||
// The FFT splits the frequency domain into an number of bins
|
||||
// A sampling frequency of 1000 and max frequency of 500 at a window size of 32 gives 16 frequency bins each 31.25Hz wide
|
||||
// Eg [0,31), [31,62), [62, 93) etc
|
|
@ -47,6 +47,7 @@
|
|||
#include "flight/gps_rescue.h"
|
||||
#include "flight/imu.h"
|
||||
#include "flight/mixer.h"
|
||||
#include "flight/rpm_filter.h"
|
||||
|
||||
#include "io/gps.h"
|
||||
|
||||
|
@ -56,7 +57,6 @@
|
|||
#include "sensors/acceleration.h"
|
||||
#include "sensors/battery.h"
|
||||
#include "sensors/gyro.h"
|
||||
#include "sensors/rpm_filter.h"
|
||||
|
||||
#include "pid.h"
|
||||
|
||||
|
|
|
@ -21,24 +21,34 @@
|
|||
|
||||
#include <math.h>
|
||||
#include <stdint.h>
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
#if defined(USE_RPM_FILTER)
|
||||
|
||||
#include "build/debug.h"
|
||||
|
||||
#include "common/filter.h"
|
||||
#include "common/maths.h"
|
||||
|
||||
#include "drivers/pwm_output_counts.h"
|
||||
|
||||
#include "flight/mixer.h"
|
||||
#include "flight/pid.h"
|
||||
|
||||
#include "pg/pg_ids.h"
|
||||
|
||||
#include "scheduler/scheduler.h"
|
||||
#include "sensors/rpm_filter.h"
|
||||
|
||||
#include "sensors/gyro.h"
|
||||
|
||||
#include "rpm_filter.h"
|
||||
|
||||
#define RPM_FILTER_MAXHARMONICS 3
|
||||
#define SECONDS_PER_MINUTE 60.0f
|
||||
#define ERPM_PER_LSB 100.0f
|
||||
#define MIN_UPDATE_T 0.001f
|
||||
|
||||
#if defined(USE_RPM_FILTER)
|
||||
|
||||
static pt1Filter_t rpmFilters[MAX_SUPPORTED_MOTORS];
|
||||
|
|
@ -62,8 +62,11 @@
|
|||
#include "fc/rc_modes.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
#include "flight/position.h"
|
||||
#if defined(USE_GYRO_DATA_ANALYSE)
|
||||
#include "flight/gyroanalyse.h"
|
||||
#endif
|
||||
#include "flight/imu.h"
|
||||
#include "flight/position.h"
|
||||
|
||||
#include "io/asyncfatfs/asyncfatfs.h"
|
||||
#include "io/beeper.h"
|
||||
|
@ -83,9 +86,6 @@
|
|||
#include "sensors/battery.h"
|
||||
#include "sensors/esc_sensor.h"
|
||||
#include "sensors/sensors.h"
|
||||
#if defined(USE_GYRO_DATA_ANALYSE)
|
||||
#include "sensors/gyroanalyse.h"
|
||||
#endif
|
||||
|
||||
#ifdef USE_HARDWARE_REVISION_DETECTION
|
||||
#include "hardware_revision.h"
|
||||
|
|
|
@ -81,6 +81,7 @@
|
|||
#include "flight/imu.h"
|
||||
#include "flight/mixer.h"
|
||||
#include "flight/pid.h"
|
||||
#include "flight/rpm_filter.h"
|
||||
|
||||
#include "io/beeper.h"
|
||||
#include "io/gps.h"
|
||||
|
@ -100,7 +101,6 @@
|
|||
#include "sensors/battery.h"
|
||||
#include "sensors/esc_sensor.h"
|
||||
#include "sensors/sensors.h"
|
||||
#include "sensors/rpm_filter.h"
|
||||
|
||||
|
||||
#define AH_SYMBOL_COUNT 9
|
||||
|
|
|
@ -66,6 +66,11 @@
|
|||
#include "fc/config.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
#ifdef USE_GYRO_DATA_ANALYSE
|
||||
#include "flight/gyroanalyse.h"
|
||||
#endif
|
||||
#include "flight/rpm_filter.h"
|
||||
|
||||
#include "io/beeper.h"
|
||||
#include "io/statusindicator.h"
|
||||
|
||||
|
@ -73,10 +78,6 @@
|
|||
|
||||
#include "sensors/boardalignment.h"
|
||||
#include "sensors/gyro.h"
|
||||
#ifdef USE_GYRO_DATA_ANALYSE
|
||||
#include "sensors/gyroanalyse.h"
|
||||
#endif
|
||||
#include "sensors/rpm_filter.h"
|
||||
#include "sensors/sensors.h"
|
||||
|
||||
#if ((FLASH_SIZE > 128) && (defined(USE_GYRO_SPI_ICM20601) || defined(USE_GYRO_SPI_ICM20689) || defined(USE_GYRO_SPI_MPU6500)))
|
||||
|
|
Loading…
Reference in New Issue