mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-15 12:25:20 +03:00
Relocated used code from board.h into appropriate headers, deleted
unused code.
This commit is contained in:
parent
3ef05c0eb9
commit
64d16e1987
15 changed files with 102 additions and 95 deletions
95
src/board.h
95
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"
|
||||
|
|
|
@ -1,7 +1,13 @@
|
|||
#include "board.h"
|
||||
#include "mw.h"
|
||||
|
||||
#include <string.h>
|
||||
|
||||
#include "sensors_acceleration.h"
|
||||
#include "telemetry_common.h"
|
||||
#include "gps_common.h"
|
||||
|
||||
|
||||
#ifndef FLASH_PAGE_COUNT
|
||||
#define FLASH_PAGE_COUNT 128
|
||||
#endif
|
||||
|
|
|
@ -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
|
||||
|
|
19
src/gps_common.h
Normal file
19
src/gps_common.h
Normal file
|
@ -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;
|
|
@ -1,6 +1,7 @@
|
|||
#include "board.h"
|
||||
#include "mw.h"
|
||||
|
||||
#include "rx.h"
|
||||
#include "telemetry_common.h"
|
||||
|
||||
core_t core;
|
||||
|
|
1
src/mw.c
1
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
|
||||
|
|
|
@ -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;
|
||||
|
|
8
src/rx.h
Normal file
8
src/rx.h
Normal file
|
@ -0,0 +1,8 @@
|
|||
#pragma once
|
||||
|
||||
typedef enum {
|
||||
SERIALRX_SPEKTRUM1024 = 0,
|
||||
SERIALRX_SPEKTRUM2048 = 1,
|
||||
SERIALRX_SBUS = 2,
|
||||
SERIALRX_SUMD = 3,
|
||||
} SerialRXType;
|
|
@ -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
|
||||
|
|
|
@ -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);
|
||||
|
|
|
@ -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,
|
||||
|
|
|
@ -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.
|
||||
|
|
|
@ -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;
|
||||
|
|
|
@ -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)
|
||||
|
|
|
@ -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);
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue