Merge pull request #637 from martinbudden/bf_tidy_sensors

Minor tidy of sensor code
This commit is contained in:
Martin Budden 2016-06-29 18:10:49 +01:00 committed by GitHub
commit 94f95d6f16
8 changed files with 19 additions and 22 deletions

View File

@ -38,8 +38,6 @@
#include "accgyro_mpu.h"
#include "accgyro_mpu6050.h"
extern uint8_t mpuLowPassFilter;
//#define DEBUG_MPU_DATA_READY_INTERRUPT
// MPU6050, Standard address 0x68

View File

@ -29,10 +29,9 @@ typedef enum {
ACC_MPU6000 = 7,
ACC_MPU6500 = 8,
ACC_FAKE = 9,
ACC_MAX = ACC_FAKE
} accelerationSensor_e;
#define ACC_MAX ACC_FAKE
extern sensor_align_e accAlign;
extern acc_t acc;
extern uint32_t accTargetLooptime;

View File

@ -22,11 +22,11 @@ typedef enum {
BARO_NONE = 1,
BARO_BMP085 = 2,
BARO_MS5611 = 3,
BARO_BMP280 = 4
BARO_BMP280 = 4,
BARO_MAX = BARO_BMP280
} baroSensor_e;
#define BARO_SAMPLE_COUNT_MAX 48
#define BARO_MAX BARO_MS5611
typedef struct barometerConfig_s {
uint8_t baro_sample_count; // size of baro filter array
@ -38,7 +38,6 @@ typedef struct barometerConfig_s {
extern int32_t BaroAlt;
extern int32_t baroTemperature; // Use temperature for telemetry
#ifdef BARO
void useBarometerConfig(barometerConfig_t *barometerConfigToUse);
bool isBaroCalibrationComplete(void);
void baroSetCalibrationCycles(uint16_t calibrationCyclesRequired);
@ -46,4 +45,3 @@ uint32_t baroUpdate(void);
bool isBaroReady(void);
int32_t baroCalculateAltitude(void);
void performBaroCalibrationCycle(void);
#endif

View File

@ -23,15 +23,13 @@ typedef enum {
MAG_NONE = 1,
MAG_HMC5883 = 2,
MAG_AK8975 = 3,
MAG_AK8963 = 4
MAG_AK8963 = 4,
MAG_MAX = MAG_AK8963
} magSensor_e;
#define MAG_MAX MAG_AK8963
#ifdef MAG
void compassInit(void);
void updateCompass(flightDynamicsTrims_t *magZero);
#endif
union flightDynamicsTrims_u;
void updateCompass(union flightDynamicsTrims_u *magZero);
extern int32_t magADC[XYZ_AXIS_COUNT];

View File

@ -41,7 +41,7 @@ sensor_align_e gyroAlign = 0;
int32_t gyroADC[XYZ_AXIS_COUNT];
float gyroADCf[XYZ_AXIS_COUNT];
static int32_t gyroZero[FLIGHT_DYNAMICS_INDEX_COUNT] = { 0, 0, 0 };
static int32_t gyroZero[XYZ_AXIS_COUNT] = { 0, 0, 0 };
static const gyroConfig_t *gyroConfig;
static biquad_t gyroFilterState[XYZ_AXIS_COUNT];
static uint8_t gyroSoftLpfHz;
@ -160,5 +160,9 @@ void gyroUpdate(void)
gyroADCf[axis] = applyBiQuadFilter((float)gyroADC[axis], &gyroFilterState[axis]);
gyroADC[axis] = lrintf(gyroADCf[axis]);
}
} else {
for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) {
gyroADCf[axis] = gyroADC[axis];
}
}
}

View File

@ -27,7 +27,8 @@ typedef enum {
GYRO_MPU6000,
GYRO_MPU6500,
GYRO_MPU9250,
GYRO_FAKE
GYRO_FAKE,
GYRO_MAX = GYRO_FAKE
} gyroSensor_e;
extern gyro_t gyro;

View File

@ -81,7 +81,7 @@ extern baro_t baro;
extern acc_t acc;
extern sensor_align_e gyroAlign;
uint8_t detectedSensors[MAX_SENSORS_TO_DETECT] = { GYRO_NONE, ACC_NONE, BARO_NONE, MAG_NONE };
uint8_t detectedSensors[SENSOR_INDEX_COUNT] = { GYRO_NONE, ACC_NONE, BARO_NONE, MAG_NONE };
const extiConfig_t *selectMPUIntExtiConfig(void)

View File

@ -21,12 +21,11 @@ typedef enum {
SENSOR_INDEX_GYRO = 0,
SENSOR_INDEX_ACC,
SENSOR_INDEX_BARO,
SENSOR_INDEX_MAG
SENSOR_INDEX_MAG,
SENSOR_INDEX_COUNT
} sensorIndex_e;
#define MAX_SENSORS_TO_DETECT (SENSOR_INDEX_MAG + 1)
extern uint8_t detectedSensors[MAX_SENSORS_TO_DETECT];
extern uint8_t detectedSensors[SENSOR_INDEX_COUNT];
typedef struct int16_flightDynamicsTrims_s {
int16_t roll;
@ -34,7 +33,7 @@ typedef struct int16_flightDynamicsTrims_s {
int16_t yaw;
} flightDynamicsTrims_def_t;
typedef union {
typedef union flightDynamicsTrims_u {
int16_t raw[3];
flightDynamicsTrims_def_t values;
} flightDynamicsTrims_t;