1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-20 23:05:19 +03:00

Update compass drivers so they do not include "board.h". It is now clear

what all compass drivers need to compile and what was unnecessarily
included before.

LED macros now moved into light_led.h
This commit is contained in:
Dominic Clifton 2014-04-17 12:33:59 +01:00
parent 1205765b4c
commit b6232573c0
11 changed files with 55 additions and 47 deletions

View file

@ -118,27 +118,7 @@ typedef uint16_t (* rcReadRawDataPtr)(uint8_t chan); // used by receiver
typedef void (* pidControllerFuncPtr)(void); // pid controller function prototype
#include "platform.h"
// Helpful macros
#ifdef LED0
#define LED0_TOGGLE digitalToggle(LED0_GPIO, LED0_PIN);
#define LED0_OFF digitalHi(LED0_GPIO, LED0_PIN);
#define LED0_ON digitalLo(LED0_GPIO, LED0_PIN);
#else
#define LED0_TOGGLE
#define LED0_OFF
#define LED0_ON
#endif
#ifdef LED1
#define LED1_TOGGLE digitalToggle(LED1_GPIO, LED1_PIN);
#define LED1_OFF digitalHi(LED1_GPIO, LED1_PIN);
#define LED1_ON digitalLo(LED1_GPIO, LED1_PIN);
#else
#define LED1_TOGGLE
#define LED1_OFF
#define LED1_ON
#endif
#include "drivers/light_led.h"
#ifdef BEEP_GPIO
#define BEEP_TOGGLE digitalToggle(BEEP_GPIO, BEEP_PIN);

View file

@ -1,5 +1,4 @@
#pragma once
// sensor orientation
void alignSensors(int16_t *src, int16_t *dest, uint8_t rotation);
void initBoardAlignment(void);

View file

@ -4,15 +4,15 @@
#include <platform.h>
#include "accgyro_common.h"
#include <sensors_common.h>
#include "accgyro_adxl345.h"
#include "sensors_common.h"
#include "system_common.h"
#include "bus_i2c.h"
#include "boardalignment.h"
#include "accgyro_adxl345.h"
// ADXL345, Alternative address mode 0x53
#define ADXL345_ADDRESS 0x53
@ -42,8 +42,6 @@
#define ADXL345_RANGE_16G 0x03
#define ADXL345_FIFO_STREAM 0x80
extern uint16_t acc_1G;
static void adxl345Init(sensor_align_e align);
static void adxl345Read(int16_t *accelData);

View file

@ -19,8 +19,6 @@
#define BMA280_PMU_BW 0x10
#define BMA280_PMU_RANGE 0x0F
extern uint16_t acc_1G;
static void bma280Init(sensor_align_e align);
static void bma280Read(int16_t *accelData);

View file

@ -1,13 +1,3 @@
#pragma once
typedef enum {
ALIGN_DEFAULT = 0, // driver-provided alignment
CW0_DEG = 1,
CW90_DEG = 2,
CW180_DEG = 3,
CW270_DEG = 4,
CW0_DEG_FLIP = 5,
CW90_DEG_FLIP = 6,
CW180_DEG_FLIP = 7,
CW270_DEG_FLIP = 8
} sensor_align_e;
extern uint16_t acc_1G;

View file

@ -12,10 +12,6 @@
#include "adc_fy90q.h"
//#include "boardalignment.h"
extern uint16_t acc_1G;
static void adcAccRead(int16_t *accelData);
static void adcGyroRead(int16_t *gyroData);
static void adcDummyInit(sensor_align_e align);

View file

@ -61,7 +61,6 @@
#define MMA8452_CTRL_REG1_LNOISE 0x04
#define MMA8452_CTRL_REG1_ACTIVE 0x01
extern uint16_t acc_1G;
static uint8_t device_id;
static sensor_align_e accAlign = CW90_DEG;

View file

@ -132,7 +132,6 @@ static void mpu6050AccRead(int16_t *accData);
static void mpu6050GyroInit(sensor_align_e align);
static void mpu6050GyroRead(int16_t *gyroData);
extern uint16_t acc_1G;
static uint8_t mpuAccelHalf = 0;
bool mpu6050Detect(sensor_t *acc, sensor_t *gyro, uint16_t lpf, uint8_t *scale)

View file

@ -1,7 +1,22 @@
#include "board.h"
#include <stdbool.h>
#include <stdint.h>
#include <math.h>
#include "platform.h"
#include "system_common.h"
#include "gpio_common.h"
#include "bus_i2c.h"
#include "light_led.h"
#include "boardalignment.h"
#include "sensors_common.h"
#include "maths.h"
#include "compass_hmc5883l.h"
// HMC5883L, default address 0x1E
// PB12 connected to MAG_DRDY on rev4 hardware
// PC14 connected to MAG_DRDY on rev5 hardware

22
src/drivers/light_led.h Normal file
View file

@ -0,0 +1,22 @@
#pragma once
// Helpful macros
#ifdef LED0
#define LED0_TOGGLE digitalToggle(LED0_GPIO, LED0_PIN);
#define LED0_OFF digitalHi(LED0_GPIO, LED0_PIN);
#define LED0_ON digitalLo(LED0_GPIO, LED0_PIN);
#else
#define LED0_TOGGLE
#define LED0_OFF
#define LED0_ON
#endif
#ifdef LED1
#define LED1_TOGGLE digitalToggle(LED1_GPIO, LED1_PIN);
#define LED1_OFF digitalHi(LED1_GPIO, LED1_PIN);
#define LED1_ON digitalLo(LED1_GPIO, LED1_PIN);
#else
#define LED1_TOGGLE
#define LED1_OFF
#define LED1_ON
#endif

View file

@ -1,5 +1,17 @@
#pragma once
typedef enum {
ALIGN_DEFAULT = 0, // driver-provided alignment
CW0_DEG = 1,
CW90_DEG = 2,
CW180_DEG = 3,
CW270_DEG = 4,
CW0_DEG_FLIP = 5,
CW90_DEG_FLIP = 6,
CW180_DEG_FLIP = 7,
CW270_DEG_FLIP = 8
} sensor_align_e;
typedef void (* sensorInitFuncPtr)(sensor_align_e align); // sensor init prototype
typedef void (* sensorReadFuncPtr)(int16_t *data); // sensor read and align prototype