diff --git a/src/board.h b/src/board.h index 64c715360d..cf1d29e590 100755 --- a/src/board.h +++ b/src/board.h @@ -23,101 +23,6 @@ #include "sensors_common.h" #include "axis.h" -typedef enum { - SENSOR_GYRO = 1 << 0, // always present - SENSOR_ACC = 1 << 1, - SENSOR_BARO = 1 << 2, - SENSOR_MAG = 1 << 3, - SENSOR_SONAR = 1 << 4, - SENSOR_GPS = 1 << 5, - SENSOR_GPSMAG = 1 << 6, -} AvailableSensors; - -// Type of accelerometer used/detected -typedef enum AccelSensors { - ACC_DEFAULT = 0, - ACC_ADXL345 = 1, - ACC_MPU6050 = 2, - ACC_MMA8452 = 3, - ACC_BMA280 = 4, - ACC_NONE = 5 -} AccelSensors; - -typedef enum { - FEATURE_PPM = 1 << 0, - FEATURE_VBAT = 1 << 1, - FEATURE_INFLIGHT_ACC_CAL = 1 << 2, - FEATURE_SERIALRX = 1 << 3, - FEATURE_MOTOR_STOP = 1 << 4, - FEATURE_SERVO_TILT = 1 << 5, - FEATURE_SOFTSERIAL = 1 << 6, - FEATURE_LED_RING = 1 << 7, - FEATURE_GPS = 1 << 8, - FEATURE_FAILSAFE = 1 << 9, - FEATURE_SONAR = 1 << 10, - FEATURE_TELEMETRY = 1 << 11, - FEATURE_POWERMETER = 1 << 12, - FEATURE_VARIO = 1 << 13, - FEATURE_3D = 1 << 14, -} AvailableFeatures; - -typedef enum { - SERIALRX_SPEKTRUM1024 = 0, - SERIALRX_SPEKTRUM2048 = 1, - SERIALRX_SBUS = 2, - SERIALRX_SUMD = 3, -} SerialRXType; - -typedef enum { - GPS_NMEA = 0, - GPS_UBLOX, - GPS_MTK_NMEA, - GPS_MTK_BINARY, - GPS_MAG_BINARY, - GPS_HARDWARE_MAX = GPS_MAG_BINARY, -} GPSHardware; - -typedef enum { - GPS_BAUD_115200 = 0, - GPS_BAUD_57600, - GPS_BAUD_38400, - GPS_BAUD_19200, - GPS_BAUD_9600, - GPS_BAUD_MAX = GPS_BAUD_9600 -} GPSBaudRates; - -typedef enum { - TELEMETRY_PROVIDER_FRSKY = 0, - TELEMETRY_PROVIDER_HOTT, - TELEMETRY_PROVIDER_MAX = TELEMETRY_PROVIDER_HOTT -} TelemetryProvider; - -typedef enum { - TELEMETRY_PORT_UART = 0, - TELEMETRY_PORT_SOFTSERIAL_1, // Requires FEATURE_SOFTSERIAL - TELEMETRY_PORT_SOFTSERIAL_2, // Requires FEATURE_SOFTSERIAL - TELEMETRY_PORT_MAX = TELEMETRY_PORT_SOFTSERIAL_2 -} TelemetryPort; - -enum { - GYRO_UPDATED = 1 << 0, - ACC_UPDATED = 1 << 1, - MAG_UPDATED = 1 << 2, - TEMP_UPDATED = 1 << 3 -}; - -typedef struct sensor_data_t -{ - int16_t gyro[3]; - int16_t acc[3]; - int16_t mag[3]; - float temperature; - int updated; -} sensor_data_t; - -typedef uint16_t (* rcReadRawDataPtr)(uint8_t chan); // used by receiver driver to return channel data -typedef void (* pidControllerFuncPtr)(void); // pid controller function prototype - #include "platform.h" #include "drivers/light_led.h" #include "drivers/sound_beeper.h" diff --git a/src/config.c b/src/config.c index e58115cb0e..f2e0b60f01 100755 --- a/src/config.c +++ b/src/config.c @@ -1,7 +1,13 @@ #include "board.h" #include "mw.h" + #include +#include "sensors_acceleration.h" +#include "telemetry_common.h" +#include "gps_common.h" + + #ifndef FLASH_PAGE_COUNT #define FLASH_PAGE_COUNT 128 #endif diff --git a/src/gps_common.c b/src/gps_common.c index 28f5f5e579..59e7d98966 100644 --- a/src/gps_common.c +++ b/src/gps_common.c @@ -3,6 +3,8 @@ #include "maths.h" +#include "gps_common.h" + // GPS timeout for wrong baud rate/disconnection/etc in milliseconds (default 2.5second) #define GPS_TIMEOUT (2500) // How many entries in gpsInitData array below diff --git a/src/gps_common.h b/src/gps_common.h new file mode 100644 index 0000000000..0502fc6942 --- /dev/null +++ b/src/gps_common.h @@ -0,0 +1,19 @@ +#pragma once + +typedef enum { + GPS_NMEA = 0, + GPS_UBLOX, + GPS_MTK_NMEA, + GPS_MTK_BINARY, + GPS_MAG_BINARY, + GPS_HARDWARE_MAX = GPS_MAG_BINARY, +} GPSHardware; + +typedef enum { + GPS_BAUD_115200 = 0, + GPS_BAUD_57600, + GPS_BAUD_38400, + GPS_BAUD_19200, + GPS_BAUD_9600, + GPS_BAUD_MAX = GPS_BAUD_9600 +} GPSBaudRates; diff --git a/src/main.c b/src/main.c index 91bf8b76f0..00b0e84fb7 100755 --- a/src/main.c +++ b/src/main.c @@ -1,6 +1,7 @@ #include "board.h" #include "mw.h" +#include "rx.h" #include "telemetry_common.h" core_t core; diff --git a/src/mw.c b/src/mw.c index 821daa54f3..2ac563703e 100755 --- a/src/mw.c +++ b/src/mw.c @@ -5,6 +5,7 @@ #include "telemetry_common.h" #include "flight_common.h" #include "typeconversion.h" +#include "rx.h" #include "maths.h" // June 2013 V2.2-dev diff --git a/src/runtime_config.h b/src/runtime_config.h index 0544f380b4..73b49bbb8c 100644 --- a/src/runtime_config.h +++ b/src/runtime_config.h @@ -1,3 +1,23 @@ +#pragma once + +typedef enum { + FEATURE_PPM = 1 << 0, + FEATURE_VBAT = 1 << 1, + FEATURE_INFLIGHT_ACC_CAL = 1 << 2, + FEATURE_SERIALRX = 1 << 3, + FEATURE_MOTOR_STOP = 1 << 4, + FEATURE_SERVO_TILT = 1 << 5, + FEATURE_SOFTSERIAL = 1 << 6, + FEATURE_LED_RING = 1 << 7, + FEATURE_GPS = 1 << 8, + FEATURE_FAILSAFE = 1 << 9, + FEATURE_SONAR = 1 << 10, + FEATURE_TELEMETRY = 1 << 11, + FEATURE_POWERMETER = 1 << 12, + FEATURE_VARIO = 1 << 13, + FEATURE_3D = 1 << 14, +} AvailableFeatures; + // Core runtime settings typedef struct core_t { serialPort_t *mainport; @@ -9,4 +29,7 @@ typedef struct core_t { bool useServo; // feature SERVO_TILT or wing/airplane mixers will enable this } core_t; +typedef uint16_t (* rcReadRawDataPtr)(uint8_t chan); // used by receiver driver to return channel data +typedef void (* pidControllerFuncPtr)(void); // pid controller function prototype + extern core_t core; diff --git a/src/rx.h b/src/rx.h new file mode 100644 index 0000000000..ae48d91b14 --- /dev/null +++ b/src/rx.h @@ -0,0 +1,8 @@ +#pragma once + +typedef enum { + SERIALRX_SPEKTRUM1024 = 0, + SERIALRX_SPEKTRUM2048 = 1, + SERIALRX_SBUS = 2, + SERIALRX_SUMD = 3, +} SerialRXType; diff --git a/src/rx_spektrum.c b/src/rx_spektrum.c index f99c109f8f..c076e9cbf6 100644 --- a/src/rx_spektrum.c +++ b/src/rx_spektrum.c @@ -1,6 +1,8 @@ #include "board.h" #include "mw.h" +#include "rx.h" + // driver for spektrum satellite receiver / sbus using UART2 (freeing up more motor outputs for stuff) #define SPEK_MAX_CHANNEL 7 diff --git a/src/sensors_acceleration.h b/src/sensors_acceleration.h index 572158dbfe..323687aa39 100644 --- a/src/sensors_acceleration.h +++ b/src/sensors_acceleration.h @@ -1,4 +1,14 @@ #pragma once +// Type of accelerometer used/detected +typedef enum AccelSensors { + ACC_DEFAULT = 0, + ACC_ADXL345 = 1, + ACC_MPU6050 = 2, + ACC_MMA8452 = 3, + ACC_BMA280 = 4, + ACC_NONE = 5 +} AccelSensors; + void ACC_Common(void); void ACC_getADC(void); diff --git a/src/sensors_common.h b/src/sensors_common.h index 8ada5066e3..aa0557c0cc 100644 --- a/src/sensors_common.h +++ b/src/sensors_common.h @@ -1,5 +1,15 @@ #pragma once +typedef enum { + SENSOR_GYRO = 1 << 0, // always present + SENSOR_ACC = 1 << 1, + SENSOR_BARO = 1 << 2, + SENSOR_MAG = 1 << 3, + SENSOR_SONAR = 1 << 4, + SENSOR_GPS = 1 << 5, + SENSOR_GPSMAG = 1 << 6, +} AvailableSensors; + typedef enum { ALIGN_DEFAULT = 0, // driver-provided alignment CW0_DEG = 1, diff --git a/src/sensors_initialisation.c b/src/sensors_initialisation.c index eec0232aa2..96a4e1819d 100755 --- a/src/sensors_initialisation.c +++ b/src/sensors_initialisation.c @@ -1,6 +1,8 @@ #include "board.h" #include "mw.h" +#include "sensors_acceleration.h" + uint16_t calibratingB = 0; // baro calibration = get new ground pressure value uint16_t calibratingG = 0; uint16_t acc_1G = 256; // this is the 1G measured acceleration. diff --git a/src/serial_cli.c b/src/serial_cli.c index 40f84ec7b5..3c3e379011 100644 --- a/src/serial_cli.c +++ b/src/serial_cli.c @@ -5,6 +5,9 @@ #include "printf.h" +#include "telemetry_common.h" +#include "gps_common.h" +#include "sensors_acceleration.h" // we unset this on 'exit' extern uint8_t cliMode; diff --git a/src/telemetry_common.c b/src/telemetry_common.c index 880d15d6ed..e7569785c2 100644 --- a/src/telemetry_common.c +++ b/src/telemetry_common.c @@ -4,6 +4,8 @@ #include "telemetry_frsky.h" #include "telemetry_hott.h" +#include "telemetry_common.h" + static bool isTelemetryConfigurationValid = false; // flag used to avoid repeated configuration checks bool isTelemetryProviderFrSky(void) diff --git a/src/telemetry_common.h b/src/telemetry_common.h index 0241d6415e..c5883d0a1b 100644 --- a/src/telemetry_common.h +++ b/src/telemetry_common.h @@ -8,6 +8,19 @@ #ifndef TELEMETRY_COMMON_H_ #define TELEMETRY_COMMON_H_ +typedef enum { + TELEMETRY_PROVIDER_FRSKY = 0, + TELEMETRY_PROVIDER_HOTT, + TELEMETRY_PROVIDER_MAX = TELEMETRY_PROVIDER_HOTT +} TelemetryProvider; + +typedef enum { + TELEMETRY_PORT_UART = 0, + TELEMETRY_PORT_SOFTSERIAL_1, // Requires FEATURE_SOFTSERIAL + TELEMETRY_PORT_SOFTSERIAL_2, // Requires FEATURE_SOFTSERIAL + TELEMETRY_PORT_MAX = TELEMETRY_PORT_SOFTSERIAL_2 +} TelemetryPort; + // telemetry void initTelemetry(void); void checkTelemetryState(void);