Merge pull request #7467 from mikeller/reorganise_interfaces

Reorganised interfaces, putting them where they are used.
This commit is contained in:
Michael Keller 2019-01-28 00:14:14 +13:00 committed by GitHub
commit 4bff464b92
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
36 changed files with 103 additions and 83 deletions

View File

@ -7,6 +7,8 @@ COMMON_SRC = \
$(addprefix pg/,$(notdir $(wildcard $(SRC_DIR)/pg/*.c))) \ $(addprefix pg/,$(notdir $(wildcard $(SRC_DIR)/pg/*.c))) \
$(addprefix common/,$(notdir $(wildcard $(SRC_DIR)/common/*.c))) \ $(addprefix common/,$(notdir $(wildcard $(SRC_DIR)/common/*.c))) \
$(addprefix config/,$(notdir $(wildcard $(SRC_DIR)/config/*.c))) \ $(addprefix config/,$(notdir $(wildcard $(SRC_DIR)/config/*.c))) \
cli/cli.c \
cli/settings.c \
drivers/adc.c \ drivers/adc.c \
drivers/buf_writer.c \ drivers/buf_writer.c \
drivers/bus.c \ drivers/bus.c \
@ -44,17 +46,17 @@ COMMON_SRC = \
fc/hardfaults.c \ fc/hardfaults.c \
fc/tasks.c \ fc/tasks.c \
fc/runtime_config.c \ fc/runtime_config.c \
interface/msp.c \
interface/msp_box.c \
interface/tramp_protocol.c \
interface/smartaudio_protocol.c \
io/beeper.c \ io/beeper.c \
io/piniobox.c \ io/piniobox.c \
io/serial.c \ io/serial.c \
io/smartaudio_protocol.c \
io/statusindicator.c \ io/statusindicator.c \
io/tramp_protocol.c \
io/transponder_ir.c \ io/transponder_ir.c \
io/usb_cdc_hid.c \ io/usb_cdc_hid.c \
io/usb_msc.c \ io/usb_msc.c \
msp/msp.c \
msp/msp_box.c \
msp/msp_serial.c \ msp/msp_serial.c \
scheduler/scheduler.c \ scheduler/scheduler.c \
sensors/adcinternal.c \ sensors/adcinternal.c \
@ -86,8 +88,6 @@ COMMON_SRC = \
flight/pid.c \ flight/pid.c \
flight/servos.c \ flight/servos.c \
flight/servos_tricopter.c \ flight/servos_tricopter.c \
interface/cli.c \
interface/settings.c \
io/serial_4way.c \ io/serial_4way.c \
io/serial_4way_avrootloader.c \ io/serial_4way_avrootloader.c \
io/serial_4way_stk500v2.c \ io/serial_4way_stk500v2.c \
@ -248,6 +248,8 @@ SPEED_OPTIMISED_SRC := $(SPEED_OPTIMISED_SRC) \
SIZE_OPTIMISED_SRC := $(SIZE_OPTIMISED_SRC) \ SIZE_OPTIMISED_SRC := $(SIZE_OPTIMISED_SRC) \
bus_bst_stm32f30x.c \ bus_bst_stm32f30x.c \
cli/cli.c \
cli/settings.c \
drivers/barometer/barometer_bmp085.c \ drivers/barometer/barometer_bmp085.c \
drivers/barometer/barometer_bmp280.c \ drivers/barometer/barometer_bmp280.c \
drivers/barometer/barometer_fake.c \ drivers/barometer/barometer_fake.c \
@ -285,8 +287,6 @@ SIZE_OPTIMISED_SRC := $(SIZE_OPTIMISED_SRC) \
config/feature.c \ config/feature.c \
config/config_streamer.c \ config/config_streamer.c \
i2c_bst.c \ i2c_bst.c \
interface/cli.c \
interface/settings.c \
io/dashboard.c \ io/dashboard.c \
io/osd.c \ io/osd.c \
io/serial.c \ io/serial.c \

View File

@ -44,6 +44,8 @@ extern uint8_t __config_end;
#include "build/debug.h" #include "build/debug.h"
#include "build/version.h" #include "build/version.h"
#include "cli/settings.h"
#include "cms/cms.h" #include "cms/cms.h"
#include "common/axis.h" #include "common/axis.h"
@ -102,12 +104,6 @@ extern uint8_t __config_end;
#include "flight/position.h" #include "flight/position.h"
#include "flight/servos.h" #include "flight/servos.h"
#include "interface/cli.h"
#include "interface/msp.h"
#include "interface/msp_box.h"
#include "interface/msp_protocol.h"
#include "interface/settings.h"
#include "io/asyncfatfs/asyncfatfs.h" #include "io/asyncfatfs/asyncfatfs.h"
#include "io/beeper.h" #include "io/beeper.h"
#include "io/flashfs.h" #include "io/flashfs.h"
@ -121,6 +117,10 @@ extern uint8_t __config_end;
#include "io/vtx_control.h" #include "io/vtx_control.h"
#include "io/vtx.h" #include "io/vtx.h"
#include "msp/msp.h"
#include "msp/msp_box.h"
#include "msp/msp_protocol.h"
#include "pg/adc.h" #include "pg/adc.h"
#include "pg/beeper.h" #include "pg/beeper.h"
#include "pg/beeper_dev.h" #include "pg/beeper_dev.h"
@ -160,6 +160,8 @@ extern uint8_t __config_end;
#include "telemetry/frsky_hub.h" #include "telemetry/frsky_hub.h"
#include "telemetry/telemetry.h" #include "telemetry/telemetry.h"
#include "cli.h"
static serialPort_t *cliPort; static serialPort_t *cliPort;

View File

@ -54,8 +54,6 @@
#include "flight/position.h" #include "flight/position.h"
#include "flight/servos.h" #include "flight/servos.h"
#include "interface/settings.h"
#include "io/beeper.h" #include "io/beeper.h"
#include "io/dashboard.h" #include "io/dashboard.h"
#include "io/gimbal.h" #include "io/gimbal.h"
@ -109,6 +107,9 @@
#include "telemetry/ibus_shared.h" #include "telemetry/ibus_shared.h"
#include "telemetry/telemetry.h" #include "telemetry/telemetry.h"
#include "settings.h"
// Sensor names (used in lookup tables for *_hardware settings and in status command output) // Sensor names (used in lookup tables for *_hardware settings and in status command output)
// sync with accelerationSensor_e // sync with accelerationSensor_e
const char * const lookupTableAccHardware[] = { const char * const lookupTableAccHardware[] = {

View File

@ -33,11 +33,8 @@
#include "build/version.h" #include "build/version.h"
#include "drivers/system.h"
#include "cms/cms.h" #include "cms/cms.h"
#include "cms/cms_types.h" #include "cms/cms_types.h"
#include "cms/cms_menu_builtin.h"
// Sub menus // Sub menus
@ -55,14 +52,18 @@
#include "cms/cms_menu_vtx_smartaudio.h" #include "cms/cms_menu_vtx_smartaudio.h"
#include "cms/cms_menu_vtx_tramp.h" #include "cms/cms_menu_vtx_tramp.h"
#include "drivers/system.h"
#include "msp/msp_protocol.h" // XXX for FC identification... not available elsewhere
#include "cms_menu_builtin.h"
// Info // Info
static char infoGitRev[GIT_SHORT_REVISION_LENGTH + 1]; static char infoGitRev[GIT_SHORT_REVISION_LENGTH + 1];
static char infoTargetName[] = __TARGET__; static char infoTargetName[] = __TARGET__;
#include "interface/msp_protocol.h" // XXX for FC identification... not available elsewhere
static long cmsx_InfoInit(void) static long cmsx_InfoInit(void)
{ {
int i; int i;

View File

@ -29,19 +29,21 @@
#include "build/version.h" #include "build/version.h"
#include "cli/settings.h"
#include "cms/cms.h" #include "cms/cms.h"
#include "cms/cms_types.h" #include "cms/cms_types.h"
#include "cms/cms_menu_ledstrip.h"
#include "config/feature.h" #include "config/feature.h"
#include "pg/pg.h"
#include "pg/pg_ids.h"
#include "fc/config.h" #include "fc/config.h"
#include "io/ledstrip.h" #include "io/ledstrip.h"
#include "interface/settings.h" #include "pg/pg.h"
#include "pg/pg_ids.h"
#include "cms_menu_ledstrip.h"
#ifdef USE_LED_STRIP #ifdef USE_LED_STRIP

View File

@ -29,6 +29,8 @@
#include "blackbox/blackbox.h" #include "blackbox/blackbox.h"
#include "cli/cli.h"
#include "common/axis.h" #include "common/axis.h"
#include "common/filter.h" #include "common/filter.h"
#include "common/maths.h" #include "common/maths.h"
@ -64,8 +66,6 @@
#include "msp/msp_serial.h" #include "msp/msp_serial.h"
#include "interface/cli.h"
#include "io/beeper.h" #include "io/beeper.h"
#include "io/gps.h" #include "io/gps.h"
#include "io/motors.h" #include "io/motors.h"

View File

@ -27,6 +27,8 @@
#include "blackbox/blackbox.h" #include "blackbox/blackbox.h"
#include "cli/cli.h"
#include "common/axis.h" #include "common/axis.h"
#include "common/color.h" #include "common/color.h"
#include "common/maths.h" #include "common/maths.h"
@ -88,13 +90,11 @@
#include "fc/runtime_config.h" #include "fc/runtime_config.h"
#include "fc/dispatch.h" #include "fc/dispatch.h"
#include "interface/cli.h"
#include "interface/msp.h"
#ifdef USE_PERSISTENT_MSC_RTC #ifdef USE_PERSISTENT_MSC_RTC
#include "msc/usbd_storage.h" #include "msc/usbd_storage.h"
#endif #endif
#include "msp/msp.h"
#include "msp/msp_serial.h" #include "msp/msp_serial.h"
#include "pg/adc.h" #include "pg/adc.h"

View File

@ -26,6 +26,8 @@
#include "build/debug.h" #include "build/debug.h"
#include "cli/cli.h"
#include "cms/cms.h" #include "cms/cms.h"
#include "common/color.h" #include "common/color.h"
@ -56,9 +58,6 @@
#include "flight/mixer.h" #include "flight/mixer.h"
#include "flight/pid.h" #include "flight/pid.h"
#include "interface/cli.h"
#include "interface/msp.h"
#include "io/asyncfatfs/asyncfatfs.h" #include "io/asyncfatfs/asyncfatfs.h"
#include "io/beeper.h" #include "io/beeper.h"
#include "io/dashboard.h" #include "io/dashboard.h"
@ -73,6 +72,7 @@
#include "io/usb_cdc_hid.h" #include "io/usb_cdc_hid.h"
#include "io/vtx.h" #include "io/vtx.h"
#include "msp/msp.h"
#include "msp/msp_serial.h" #include "msp/msp_serial.h"
#include "pg/rx.h" #include "pg/rx.h"

View File

@ -34,11 +34,10 @@
#include "drivers/display.h" #include "drivers/display.h"
#include "interface/msp.h"
#include "interface/msp_protocol.h"
#include "io/displayport_msp.h" #include "io/displayport_msp.h"
#include "msp/msp.h"
#include "msp/msp_protocol.h"
#include "msp/msp_serial.h" #include "msp/msp_serial.h"
// no template required since defaults are zero // no template required since defaults are zero

View File

@ -29,7 +29,7 @@
#include "common/utils.h" #include "common/utils.h"
#include "common/time.h" #include "common/time.h"
#include "interface/msp_box.h" #include "msp/msp_box.h"
#include "pg/pinio.h" #include "pg/pinio.h"
#include "pg/piniobox.h" #include "pg/piniobox.h"

View File

@ -26,13 +26,10 @@
#include "build/build_config.h" #include "build/build_config.h"
#include "cli/cli.h"
#include "common/utils.h" #include "common/utils.h"
#include "pg/pg.h"
#include "pg/pg_ids.h"
#include "fc/config.h"
#include "drivers/time.h" #include "drivers/time.h"
#include "drivers/system.h" #include "drivers/system.h"
#include "drivers/serial.h" #include "drivers/serial.h"
@ -51,12 +48,15 @@
#include "drivers/serial_usb_vcp.h" #include "drivers/serial_usb_vcp.h"
#endif #endif
#include "fc/config.h"
#include "io/serial.h" #include "io/serial.h"
#include "interface/cli.h"
#include "msp/msp_serial.h" #include "msp/msp_serial.h"
#include "pg/pg.h"
#include "pg/pg_ids.h"
#ifdef USE_TELEMETRY #ifdef USE_TELEMETRY
#include "telemetry/telemetry.h" #include "telemetry/telemetry.h"
#endif #endif

View File

@ -19,8 +19,10 @@
*/ */
#include "platform.h" #include "platform.h"
#include "common/crc.h" #include "common/crc.h"
#include "interface/smartaudio_protocol.h"
#include "smartaudio_protocol.h"
#define SMARTAUDIO_SYNC_BYTE 0xAA #define SMARTAUDIO_SYNC_BYTE 0xAA
#define SMARTAUDIO_HEADER_BYTE 0x55 #define SMARTAUDIO_HEADER_BYTE 0x55

View File

@ -19,9 +19,12 @@
*/ */
#include <string.h> #include <string.h>
#include "platform.h" #include "platform.h"
#include "common/utils.h" #include "common/utils.h"
#include "interface/tramp_protocol.h"
#include "tramp_protocol.h"
#define TRAMP_SYNC_START 0x0F #define TRAMP_SYNC_START 0x0F
#define TRAMP_SYNC_STOP 0x00 #define TRAMP_SYNC_STOP 0x00

View File

@ -25,6 +25,8 @@
#if defined(USE_VTX_COMMON) #if defined(USE_VTX_COMMON)
#include "cli/cli.h"
#include "common/maths.h" #include "common/maths.h"
#include "common/time.h" #include "common/time.h"
@ -36,15 +38,14 @@
#include "flight/failsafe.h" #include "flight/failsafe.h"
#include "io/vtx.h"
#include "io/vtx_string.h" #include "io/vtx_string.h"
#include "io/vtx_control.h" #include "io/vtx_control.h"
#include "interface/cli.h"
#include "pg/pg.h" #include "pg/pg.h"
#include "pg/pg_ids.h" #include "pg/pg_ids.h"
#include "vtx.h"
PG_REGISTER_WITH_RESET_TEMPLATE(vtxSettingsConfig_t, vtxSettingsConfig, PG_VTX_SETTINGS_CONFIG, 0); PG_REGISTER_WITH_RESET_TEMPLATE(vtxSettingsConfig_t, vtxSettingsConfig, PG_VTX_SETTINGS_CONFIG, 0);

View File

@ -78,10 +78,6 @@
#include "flight/pid.h" #include "flight/pid.h"
#include "flight/servos.h" #include "flight/servos.h"
#include "interface/msp.h"
#include "interface/msp_box.h"
#include "interface/msp_protocol.h"
#include "io/asyncfatfs/asyncfatfs.h" #include "io/asyncfatfs/asyncfatfs.h"
#include "io/beeper.h" #include "io/beeper.h"
#include "io/flashfs.h" #include "io/flashfs.h"
@ -99,6 +95,8 @@
#include "io/vtx.h" #include "io/vtx.h"
#include "io/vtx_string.h" #include "io/vtx_string.h"
#include "msp/msp_box.h"
#include "msp/msp_protocol.h"
#include "msp/msp_serial.h" #include "msp/msp_serial.h"
#include "pg/beeper.h" #include "pg/beeper.h"
@ -132,6 +130,9 @@
#include "hardware_revision.h" #include "hardware_revision.h"
#endif #endif
#include "msp.h"
static const char * const flightControllerIdentifier = BETAFLIGHT_IDENTIFIER; // 4 UPPER CASE alpha numeric characters that identify the flight controller. static const char * const flightControllerIdentifier = BETAFLIGHT_IDENTIFIER; // 4 UPPER CASE alpha numeric characters that identify the flight controller.
enum { enum {

View File

@ -35,14 +35,14 @@
#include "flight/mixer.h" #include "flight/mixer.h"
#include "interface/msp_box.h"
#include "sensors/sensors.h" #include "sensors/sensors.h"
#include "telemetry/telemetry.h" #include "telemetry/telemetry.h"
#include "pg/piniobox.h" #include "pg/piniobox.h"
#include "msp_box.h"
// permanent IDs must uniquely identify BOX meaning, DO NOT REUSE THEM! // permanent IDs must uniquely identify BOX meaning, DO NOT REUSE THEM!
static const box_t boxes[CHECKBOX_ITEM_COUNT] = { static const box_t boxes[CHECKBOX_ITEM_COUNT] = {

View File

@ -26,18 +26,19 @@
#include "build/debug.h" #include "build/debug.h"
#include "cli/cli.h"
#include "common/streambuf.h" #include "common/streambuf.h"
#include "common/utils.h" #include "common/utils.h"
#include "common/crc.h" #include "common/crc.h"
#include "drivers/system.h" #include "drivers/system.h"
#include "interface/msp.h"
#include "interface/cli.h"
#include "io/serial.h" #include "io/serial.h"
#include "msp/msp_serial.h" #include "msp/msp.h"
#include "msp_serial.h"
static mspPort_t mspPorts[MAX_MSP_PORT_COUNT]; static mspPort_t mspPorts[MAX_MSP_PORT_COUNT];

View File

@ -21,7 +21,7 @@
#pragma once #pragma once
#include "drivers/time.h" #include "drivers/time.h"
#include "interface/msp.h" #include "msp/msp.h"
// Each MSP port requires state and a receive buffer, revisit this default if someone needs more than 3 MSP ports. // Each MSP port requires state and a receive buffer, revisit this default if someone needs more than 3 MSP ports.
#define MAX_MSP_PORT_COUNT 3 #define MAX_MSP_PORT_COUNT 3

View File

@ -22,10 +22,14 @@
#ifdef USE_PINIOBOX #ifdef USE_PINIOBOX
#include "pg/pg_ids.h"
#include "piniobox.h"
#include "drivers/io.h" #include "drivers/io.h"
#include "interface/msp_box.h"
#include "msp/msp_box.h"
#include "pg/pg_ids.h"
#include "piniobox.h"
PG_REGISTER_WITH_RESET_TEMPLATE(pinioBoxConfig_t, pinioBoxConfig, PG_PINIOBOX_CONFIG, 1); PG_REGISTER_WITH_RESET_TEMPLATE(pinioBoxConfig_t, pinioBoxConfig, PG_PINIOBOX_CONFIG, 1);

View File

@ -20,7 +20,7 @@
#pragma once #pragma once
#include "interface/crsf_protocol.h" #include "rx/crsf_protocol.h"
#define CRSF_PORT_OPTIONS (SERIAL_STOPBITS_1 | SERIAL_PARITY_NO) #define CRSF_PORT_OPTIONS (SERIAL_STOPBITS_1 | SERIAL_PARITY_NO)

View File

@ -254,7 +254,8 @@ void currentMeterESCReadMotor(uint8_t motorNumber, currentMeter_t *meter)
#ifdef USE_MSP_CURRENT_METER #ifdef USE_MSP_CURRENT_METER
#include "common/streambuf.h" #include "common/streambuf.h"
#include "interface/msp_protocol.h"
#include "msp/msp_protocol.h"
#include "msp/msp_serial.h" #include "msp/msp_serial.h"
currentMeterMSPState_t currentMeterMSPState; currentMeterMSPState_t currentMeterMSPState;

View File

@ -51,21 +51,22 @@
#include "flight/imu.h" #include "flight/imu.h"
#include "flight/position.h" #include "flight/position.h"
#include "interface/crsf_protocol.h"
#include "io/displayport_crsf.h" #include "io/displayport_crsf.h"
#include "io/gps.h" #include "io/gps.h"
#include "io/serial.h" #include "io/serial.h"
#include "rx/crsf.h" #include "rx/crsf.h"
#include "rx/crsf_protocol.h"
#include "sensors/battery.h" #include "sensors/battery.h"
#include "sensors/sensors.h" #include "sensors/sensors.h"
#include "telemetry/telemetry.h" #include "telemetry/telemetry.h"
#include "telemetry/crsf.h"
#include "telemetry/msp_shared.h" #include "telemetry/msp_shared.h"
#include "telemetry/crsf.h"
#define CRSF_CYCLETIME_US 100000 // 100ms, 10 Hz #define CRSF_CYCLETIME_US 100000 // 100ms, 10 Hz
#define CRSF_DEVICEINFO_VERSION 0x01 #define CRSF_DEVICEINFO_VERSION 0x01
#define CRSF_DEVICEINFO_PARAMETER_COUNT 0 #define CRSF_DEVICEINFO_PARAMETER_COUNT 0

View File

@ -24,7 +24,8 @@
#include <stdint.h> #include <stdint.h>
#include "common/time.h" #include "common/time.h"
#include "interface/crsf_protocol.h"
#include "rx/crsf_protocol.h"
#define CRSF_MSP_RX_BUF_SIZE 128 #define CRSF_MSP_RX_BUF_SIZE 128
#define CRSF_MSP_TX_BUF_SIZE 128 #define CRSF_MSP_TX_BUF_SIZE 128

View File

@ -30,8 +30,8 @@
#include "common/utils.h" #include "common/utils.h"
#include "interface/msp.h" #include "msp/msp.h"
#include "interface/msp_protocol.h" #include "msp/msp_protocol.h"
#include "telemetry/crsf.h" #include "telemetry/crsf.h"
#include "telemetry/msp_shared.h" #include "telemetry/msp_shared.h"

View File

@ -55,13 +55,13 @@
#include "flight/pid.h" #include "flight/pid.h"
#include "flight/position.h" #include "flight/position.h"
#include "interface/msp.h"
#include "io/beeper.h" #include "io/beeper.h"
#include "io/gps.h" #include "io/gps.h"
#include "io/motors.h" #include "io/motors.h"
#include "io/serial.h" #include "io/serial.h"
#include "msp/msp.h"
#include "rx/rx.h" #include "rx/rx.h"
#include "pg/pg.h" #include "pg/pg.h"

View File

@ -95,7 +95,7 @@ blackbox_encoding_unittest_SRC := \
$(USER_DIR)/common/typeconversion.c $(USER_DIR)/common/typeconversion.c
cli_unittest_SRC := \ cli_unittest_SRC := \
$(USER_DIR)/interface/cli.c \ $(USER_DIR)/cli/cli.c \
$(USER_DIR)/config/feature.c \ $(USER_DIR)/config/feature.c \
$(USER_DIR)/pg/pg.c \ $(USER_DIR)/pg/pg.c \
$(USER_DIR)/common/typeconversion.c $(USER_DIR)/common/typeconversion.c

View File

@ -27,10 +27,9 @@ extern "C" {
#include "platform.h" #include "platform.h"
#include "target.h" #include "target.h"
#include "build/version.h" #include "build/version.h"
#include "cli/cli.h"
#include "cli/settings.h"
#include "config/feature.h" #include "config/feature.h"
#include "pg/pg.h"
#include "pg/pg_ids.h"
#include "pg/rx.h"
#include "drivers/buf_writer.h" #include "drivers/buf_writer.h"
#include "drivers/vtx_common.h" #include "drivers/vtx_common.h"
#include "fc/config.h" #include "fc/config.h"
@ -39,16 +38,17 @@ extern "C" {
#include "flight/mixer.h" #include "flight/mixer.h"
#include "flight/pid.h" #include "flight/pid.h"
#include "flight/servos.h" #include "flight/servos.h"
#include "interface/cli.h"
#include "interface/msp.h"
#include "interface/msp_box.h"
#include "interface/settings.h"
#include "io/beeper.h" #include "io/beeper.h"
#include "io/ledstrip.h" #include "io/ledstrip.h"
#include "io/osd.h" #include "io/osd.h"
#include "io/serial.h" #include "io/serial.h"
#include "io/vtx.h" #include "io/vtx.h"
#include "msp/msp.h"
#include "msp/msp_box.h"
#include "pg/pg.h"
#include "pg/pg_ids.h"
#include "pg/beeper.h" #include "pg/beeper.h"
#include "pg/rx.h"
#include "rx/rx.h" #include "rx/rx.h"
#include "scheduler/scheduler.h" #include "scheduler/scheduler.h"
#include "sensors/battery.h" #include "sensors/battery.h"

View File

@ -47,11 +47,11 @@ extern "C" {
#include "fc/config.h" #include "fc/config.h"
#include "flight/imu.h" #include "flight/imu.h"
#include "interface/msp.h"
#include "io/serial.h" #include "io/serial.h"
#include "io/gps.h" #include "io/gps.h"
#include "msp/msp.h"
#include "rx/rx.h" #include "rx/rx.h"
#include "rx/crsf.h" #include "rx/crsf.h"