1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-24 00:35:39 +03:00
betaflight/src/board.h
Dominic Clifton 38ec0b6080 Update gpio/ledring drivers so they do not include "board.h". It is now
clear what all gpio/ledring drivers need to compile and what was
unnecessarily included before.
 
In attempting this it was clear that ledring had a dependency on the
multiwii code, this was removed by passing the led status update method
the values it needs.

It also turned out that the ROLL/PITCH defines were coming from
rc_alias_e and much unrelated code is coupled to these defines.  This
commit also includes some cleanups relating to that problem.
2014-04-17 13:56:23 +01:00

188 lines
4.7 KiB
C
Executable file

/*
* This file is deprecated. All this code belongs elsewhere - create appropriate headers and include them.
*/
#pragma once
#include <stdbool.h>
#include <stdlib.h>
#include <stdint.h>
#define __USE_C99_MATH // for roundf()
#include <math.h>
#include <ctype.h>
#include <string.h>
#include <stdio.h>
#include "platform.h"
#include "drivers/accgyro_common.h"
#include "drivers/gpio_common.h"
#include "drivers/system_common.h"
#include "drivers/altimeter_common.h"
#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"
#ifdef BEEP_GPIO
#define BEEP_TOGGLE digitalToggle(BEEP_GPIO, BEEP_PIN);
#define BEEP_OFF systemBeep(false);
#define BEEP_ON systemBeep(true);
#else
#define BEEP_TOGGLE ;
#define BEEP_OFF ;
#define BEEP_ON ;
#endif
#include "boardalignment.h"
#include "battery.h"
#include "math.h"
#ifdef FY90Q
// FY90Q
#include "drivers/adc_common.h"
#include "drivers/adc_fy90q.h"
#include "drivers/bus_i2c.h"
#include "drivers/bus_spi.h"
#include "drivers/pwm_common.h"
#include "drivers/timer_common.h"
#include "drivers/serial_common.h"
#include "drivers/serial_uart.h"
#else
#ifdef OLIMEXINO
// OLIMEXINO
#include "drivers/adc_common.h"
#include "drivers/bus_i2c.h"
#include "drivers/bus_spi.h"
#include "drivers/accgyro_adxl345.h"
#include "drivers/accgyro_mpu3050.h"
#include "drivers/accgyro_mpu6050.h"
#include "drivers/accgyro_l3g4200d.h"
#include "drivers/pwm_common.h"
#include "drivers/timer_common.h"
#include "drivers/serial_common.h"
#include "drivers/serial_uart.h"
#include "drivers/serial_softserial.h"
#else
// AfroFlight32
#include "drivers/adc_common.h"
#include "drivers/accgyro_adxl345.h"
#include "drivers/accgyro_bma280.h"
#include "drivers/altimeter_bmp085.h"
#include "drivers/altimeter_ms5611.h"
#include "drivers/compass_hmc5883l.h"
#include "drivers/bus_i2c.h"
#include "drivers/bus_spi.h"
#include "drivers/light_ledring.h"
#include "drivers/accgyro_mma845x.h"
#include "drivers/accgyro_mpu3050.h"
#include "drivers/accgyro_mpu6050.h"
#include "drivers/accgyro_l3g4200d.h"
#include "drivers/pwm_common.h"
#include "drivers/timer_common.h"
#include "drivers/serial_common.h"
#include "drivers/serial_uart.h"
#include "drivers/serial_softserial.h"
#include "drivers/sonar_hcsr04.h"
#endif
#endif