Cleanup sensor detection. Less code required and a similar pattern is used for each type of sensor.
This commit is contained in:
parent
77e5be5002
commit
c45efac812
|
@ -294,9 +294,6 @@ void init(void)
|
|||
}
|
||||
#endif
|
||||
|
||||
// We have these sensors; SENSORS_SET defined in board.h depending on hardware platform
|
||||
sensorsSet(SENSORS_SET);
|
||||
// drop out any sensors that don't seem to work, init all the others. halt if gyro is dead.
|
||||
sensorsOK = sensorsAutodetect(&masterConfig.sensorAlignmentConfig, masterConfig.gyro_lpf, masterConfig.acc_hardware, masterConfig.mag_hardware, currentProfile->mag_declination);
|
||||
|
||||
// if gyro was not detected due to whatever reason, we give up now.
|
||||
|
|
|
@ -37,7 +37,7 @@
|
|||
int16_t accADC[XYZ_AXIS_COUNT];
|
||||
|
||||
acc_t acc; // acc access functions
|
||||
uint8_t accHardware = ACC_DEFAULT; // which accel chip is used/detected
|
||||
accelerationSensor_e accHardware = ACC_DEFAULT; // which accel chip is used/detected
|
||||
sensor_align_e accAlign = 0;
|
||||
uint16_t acc_1G = 256; // this is the 1G measured acceleration.
|
||||
|
||||
|
|
|
@ -18,7 +18,7 @@
|
|||
#pragma once
|
||||
|
||||
// Type of accelerometer used/detected
|
||||
typedef enum AccelSensors {
|
||||
typedef enum {
|
||||
ACC_DEFAULT = 0,
|
||||
ACC_ADXL345 = 1,
|
||||
ACC_MPU6050 = 2,
|
||||
|
@ -29,7 +29,7 @@ typedef enum AccelSensors {
|
|||
ACC_SPI_MPU6500 = 7,
|
||||
ACC_FAKE = 8,
|
||||
ACC_NONE = 9
|
||||
} accelSensor_e;
|
||||
} accelerationSensor_e;
|
||||
|
||||
extern uint8_t accHardware;
|
||||
extern sensor_align_e accAlign;
|
||||
|
|
|
@ -41,6 +41,7 @@ static int32_t baroGroundPressure = 0;
|
|||
static uint32_t baroPressureSum = 0;
|
||||
|
||||
barometerConfig_t *barometerConfig;
|
||||
baroSensor_e baroHardware;
|
||||
|
||||
void useBarometerConfig(barometerConfig_t *barometerConfigToUse)
|
||||
{
|
||||
|
|
|
@ -17,6 +17,15 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
typedef enum {
|
||||
BARO_NONE = 0,
|
||||
BARO_DEFAULT = 1,
|
||||
BARO_BMP085 = 2,
|
||||
BARO_MS5611 = 3
|
||||
} baroSensor_e;
|
||||
|
||||
extern baroSensor_e baroHardware;
|
||||
|
||||
#define BARO_SAMPLE_COUNT_MAX 48
|
||||
|
||||
typedef struct barometerConfig_s {
|
||||
|
|
|
@ -40,7 +40,7 @@
|
|||
#endif
|
||||
|
||||
mag_t mag; // mag access functions
|
||||
uint8_t magHardware = MAG_DEFAULT;
|
||||
magSensor_e magHardware = MAG_DEFAULT;
|
||||
|
||||
extern uint32_t currentTime; // FIXME dependency on global variable, pass it in instead.
|
||||
|
||||
|
|
|
@ -18,7 +18,7 @@
|
|||
#pragma once
|
||||
|
||||
// Type of accelerometer used/detected
|
||||
typedef enum MagSensors {
|
||||
typedef enum {
|
||||
MAG_DEFAULT = 0,
|
||||
MAG_HMC5883 = 1,
|
||||
MAG_AK8975 = 2,
|
||||
|
|
|
@ -233,11 +233,10 @@ retry:
|
|||
}
|
||||
#endif
|
||||
case ACC_NONE: // disable ACC
|
||||
sensorsClear(SENSOR_ACC);
|
||||
break;
|
||||
case ACC_DEFAULT: // autodetect
|
||||
#ifdef USE_ACC_ADXL345
|
||||
case ACC_ADXL345: // ADXL345
|
||||
#ifdef USE_ACC_ADXL345
|
||||
acc_params.useFifo = false;
|
||||
acc_params.dataRate = 800; // unused currently
|
||||
#ifdef NAZE
|
||||
|
@ -252,10 +251,10 @@ retry:
|
|||
if (accHardwareToUse == ACC_ADXL345)
|
||||
break;
|
||||
}
|
||||
; // fallthrough
|
||||
#endif
|
||||
#ifdef USE_ACC_LSM303DLHC
|
||||
; // fallthrough
|
||||
case ACC_LSM303DLHC:
|
||||
#ifdef USE_ACC_LSM303DLHC
|
||||
if (lsm303dlhcAccDetect(&acc)) {
|
||||
#ifdef ACC_LSM303DLHC_ALIGN
|
||||
accAlign = ACC_LSM303DLHC_ALIGN;
|
||||
|
@ -264,10 +263,10 @@ retry:
|
|||
if (accHardwareToUse == ACC_LSM303DLHC)
|
||||
break;
|
||||
}
|
||||
; // fallthrough
|
||||
#endif
|
||||
#ifdef USE_ACC_MPU6050
|
||||
; // fallthrough
|
||||
case ACC_MPU6050: // MPU6050
|
||||
#ifdef USE_ACC_MPU6050
|
||||
if (mpu6050AccDetect(selectMPU6050Config(), &acc)) {
|
||||
#ifdef ACC_MPU6050_ALIGN
|
||||
accAlign = ACC_MPU6050_ALIGN;
|
||||
|
@ -276,10 +275,10 @@ retry:
|
|||
if (accHardwareToUse == ACC_MPU6050)
|
||||
break;
|
||||
}
|
||||
; // fallthrough
|
||||
#endif
|
||||
#ifdef USE_ACC_MMA8452
|
||||
; // fallthrough
|
||||
case ACC_MMA8452: // MMA8452
|
||||
#ifdef USE_ACC_MMA8452
|
||||
#ifdef NAZE
|
||||
// Not supported with this frequency
|
||||
if (hardwareRevision < NAZE32_REV5 && mma8452Detect(&acc)) {
|
||||
|
@ -293,10 +292,10 @@ retry:
|
|||
if (accHardwareToUse == ACC_MMA8452)
|
||||
break;
|
||||
}
|
||||
; // fallthrough
|
||||
#endif
|
||||
#ifdef USE_ACC_BMA280
|
||||
; // fallthrough
|
||||
case ACC_BMA280: // BMA280
|
||||
#ifdef USE_ACC_BMA280
|
||||
if (bma280Detect(&acc)) {
|
||||
#ifdef ACC_BMA280_ALIGN
|
||||
accAlign = ACC_BMA280_ALIGN;
|
||||
|
@ -305,10 +304,10 @@ retry:
|
|||
if (accHardwareToUse == ACC_BMA280)
|
||||
break;
|
||||
}
|
||||
; // fallthrough
|
||||
#endif
|
||||
#ifdef USE_ACC_SPI_MPU6000
|
||||
; // fallthrough
|
||||
case ACC_SPI_MPU6000:
|
||||
#ifdef USE_ACC_SPI_MPU6000
|
||||
if (mpu6000SpiAccDetect(&acc)) {
|
||||
#ifdef ACC_SPI_MPU6000_ALIGN
|
||||
accAlign = ACC_SPI_MPU6000_ALIGN;
|
||||
|
@ -317,10 +316,10 @@ retry:
|
|||
if (accHardwareToUse == ACC_SPI_MPU6000)
|
||||
break;
|
||||
}
|
||||
; // fallthrough
|
||||
#endif
|
||||
#ifdef USE_ACC_SPI_MPU6500
|
||||
; // fallthrough
|
||||
case ACC_SPI_MPU6500:
|
||||
#ifdef USE_ACC_SPI_MPU6500
|
||||
#ifdef NAZE
|
||||
if (hardwareRevision == NAZE32_SP && mpu6500SpiAccDetect(&acc)) {
|
||||
#else
|
||||
|
@ -333,9 +332,8 @@ retry:
|
|||
if (accHardwareToUse == ACC_SPI_MPU6500)
|
||||
break;
|
||||
}
|
||||
; // fallthrough
|
||||
#endif
|
||||
; // prevent compiler error
|
||||
; // fallthrough
|
||||
}
|
||||
|
||||
// Found anything? Check if error or ACC is really missing.
|
||||
|
@ -344,18 +342,21 @@ retry:
|
|||
// Nothing was found and we have a forced sensor that isn't present.
|
||||
accHardwareToUse = ACC_DEFAULT;
|
||||
goto retry;
|
||||
} else {
|
||||
// No ACC was detected
|
||||
sensorsClear(SENSOR_ACC);
|
||||
}
|
||||
}
|
||||
|
||||
if (accHardware != ACC_NONE) {
|
||||
sensorsSet(SENSOR_ACC);
|
||||
}
|
||||
}
|
||||
|
||||
static void detectBaro()
|
||||
{
|
||||
#ifdef BARO
|
||||
// Detect what pressure sensors are available. baro->update() is set to sensor-specific update function
|
||||
|
||||
#ifdef BARO
|
||||
baroHardware = BARO_DEFAULT;
|
||||
|
||||
#ifdef USE_BARO_BMP085
|
||||
|
||||
const bmp085Config_t *bmp085Config = NULL;
|
||||
|
@ -379,24 +380,37 @@ static void detectBaro()
|
|||
|
||||
#endif
|
||||
|
||||
#ifdef USE_BARO_MS5611
|
||||
if (ms5611Detect(&baro)) {
|
||||
sensorsSet(SENSOR_BARO);
|
||||
return;
|
||||
}
|
||||
#endif
|
||||
switch (baroHardware) {
|
||||
case BARO_DEFAULT:
|
||||
; // fallthough
|
||||
|
||||
case BARO_MS5611:
|
||||
#ifdef USE_BARO_MS5611
|
||||
if (ms5611Detect(&baro)) {
|
||||
baroHardware = BARO_MS5611;
|
||||
break;
|
||||
}
|
||||
#endif
|
||||
; // fallthough
|
||||
case BARO_BMP085:
|
||||
#ifdef USE_BARO_BMP085
|
||||
if (bmp085Detect(bmp085Config, &baro)) {
|
||||
sensorsSet(SENSOR_BARO);
|
||||
return;
|
||||
if (bmp085Detect(bmp085Config, &baro)) {
|
||||
baroHardware = BARO_BMP085;
|
||||
break;
|
||||
}
|
||||
#endif
|
||||
baroHardware = BARO_NONE; // nothing detected or enabled.
|
||||
case BARO_NONE:
|
||||
break;
|
||||
}
|
||||
#endif
|
||||
#endif
|
||||
sensorsClear(SENSOR_BARO);
|
||||
|
||||
if (baroHardware != BARO_NONE) {
|
||||
sensorsSet(SENSOR_BARO);
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
static void detectMag(uint8_t magHardwareToUse)
|
||||
static void detectMag(magSensor_e magHardwareToUse)
|
||||
{
|
||||
#ifdef USE_MAG_HMC5883
|
||||
static hmc5883Config_t *hmc5883Config = 0;
|
||||
|
@ -435,12 +449,11 @@ retry:
|
|||
|
||||
switch(magHardwareToUse) {
|
||||
case MAG_NONE: // disable MAG
|
||||
sensorsClear(SENSOR_MAG);
|
||||
break;
|
||||
case MAG_DEFAULT: // autodetect
|
||||
|
||||
#ifdef USE_MAG_HMC5883
|
||||
case MAG_HMC5883:
|
||||
#ifdef USE_MAG_HMC5883
|
||||
if (hmc5883lDetect(&mag, hmc5883Config)) {
|
||||
sensorsSet(SENSOR_MAG);
|
||||
#ifdef MAG_HMC5883_ALIGN
|
||||
|
@ -451,11 +464,11 @@ retry:
|
|||
break;
|
||||
|
||||
}
|
||||
; // fallthrough
|
||||
#endif
|
||||
; // fallthrough
|
||||
|
||||
#ifdef USE_MAG_AK8975
|
||||
case MAG_AK8975:
|
||||
#ifdef USE_MAG_AK8975
|
||||
if (ak8975detect(&mag)) {
|
||||
|
||||
sensorsSet(SENSOR_MAG);
|
||||
|
@ -466,9 +479,8 @@ retry:
|
|||
if (magHardwareToUse == MAG_AK8975)
|
||||
break;
|
||||
}
|
||||
; // fallthrough
|
||||
#endif
|
||||
; // prevent compiler error.
|
||||
; // fallthrough
|
||||
}
|
||||
|
||||
if (magHardware == MAG_DEFAULT) {
|
||||
|
@ -476,12 +488,13 @@ retry:
|
|||
// Nothing was found and we have a forced sensor that isn't present.
|
||||
magHardwareToUse = MAG_DEFAULT;
|
||||
goto retry;
|
||||
} else {
|
||||
// No MAG was detected
|
||||
sensorsClear(SENSOR_MAG);
|
||||
}
|
||||
}
|
||||
|
||||
if (magHardware != MAG_NONE) {
|
||||
sensorsSet(SENSOR_MAG);
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
void reconfigureAlignment(sensorAlignmentConfig_t *sensorAlignmentConfig)
|
||||
|
|
|
@ -86,9 +86,6 @@
|
|||
#define I2C2_SDA_PIN_SOURCE GPIO_PinSource10
|
||||
#define I2C2_SDA_CLK_SOURCE RCC_AHBPeriph_GPIOA
|
||||
|
||||
|
||||
#define SENSORS_SET (SENSOR_ACC | SENSOR_BARO | SENSOR_MAG)
|
||||
|
||||
#define BLACKBOX
|
||||
#define SERIAL_RX
|
||||
#define GPS
|
||||
|
|
|
@ -98,8 +98,6 @@
|
|||
#define RSSI_ADC_CHANNEL ADC_Channel_1
|
||||
|
||||
|
||||
#define SENSORS_SET (SENSOR_ACC)
|
||||
|
||||
#define GPS
|
||||
#define LED_STRIP
|
||||
#define LED_STRIP_TIMER TIM3
|
||||
|
|
|
@ -90,9 +90,6 @@
|
|||
#define EXTERNAL1_ADC_GPIO_PIN GPIO_Pin_3
|
||||
#define EXTERNAL1_ADC_CHANNEL ADC_Channel_9
|
||||
|
||||
|
||||
#define SENSORS_SET (SENSOR_ACC | SENSOR_BARO | SENSOR_MAG)
|
||||
|
||||
#define GPS
|
||||
#define LED_STRIP
|
||||
#if 1
|
||||
|
|
|
@ -60,8 +60,6 @@
|
|||
// #define SOFT_I2C_PB1011 // If SOFT_I2C is enabled above, need to define pinout as well (I2C1 = PB67, I2C2 = PB1011)
|
||||
// #define SOFT_I2C_PB67
|
||||
|
||||
#define SENSORS_SET (SENSOR_ACC | SENSOR_MAG)
|
||||
|
||||
#define SERIAL_RX
|
||||
|
||||
#define SPEKTRUM_BIND
|
||||
|
|
|
@ -116,8 +116,6 @@
|
|||
#define EXTERNAL1_ADC_GPIO_PIN GPIO_Pin_5
|
||||
#define EXTERNAL1_ADC_CHANNEL ADC_Channel_5
|
||||
|
||||
#define SENSORS_SET (SENSOR_ACC | SENSOR_BARO | SENSOR_MAG)
|
||||
|
||||
#define GPS
|
||||
#define LED_STRIP
|
||||
#define LED_STRIP_TIMER TIM3
|
||||
|
|
|
@ -135,8 +135,6 @@
|
|||
#define EXTERNAL1_ADC_GPIO_PIN GPIO_Pin_5
|
||||
#define EXTERNAL1_ADC_CHANNEL ADC_Channel_5
|
||||
|
||||
#define SENSORS_SET (SENSOR_ACC | SENSOR_BARO | SENSOR_MAG)
|
||||
|
||||
#define GPS
|
||||
|
||||
#define LED_STRIP
|
||||
|
|
|
@ -40,8 +40,6 @@
|
|||
#define USE_I2C
|
||||
#define I2C_DEVICE (I2CDEV_1)
|
||||
|
||||
#define SENSORS_SET (SENSOR_ACC)
|
||||
|
||||
#define GPS
|
||||
#define BLACKBOX
|
||||
#define TELEMETRY
|
||||
|
|
|
@ -103,9 +103,6 @@
|
|||
#define EXTERNAL1_ADC_GPIO_PIN GPIO_Pin_5
|
||||
#define EXTERNAL1_ADC_CHANNEL ADC_Channel_5
|
||||
|
||||
|
||||
#define SENSORS_SET (SENSOR_ACC | SENSOR_BARO | SENSOR_MAG)
|
||||
|
||||
#define GPS
|
||||
#define LED_STRIP
|
||||
#define LED_STRIP_TIMER TIM3
|
||||
|
|
|
@ -126,8 +126,6 @@
|
|||
#define EXTERNAL1_ADC_GPIO_PIN GPIO_Pin_5
|
||||
#define EXTERNAL1_ADC_CHANNEL ADC_Channel_5
|
||||
|
||||
#define SENSORS_SET (SENSOR_ACC | SENSOR_BARO | SENSOR_MAG)
|
||||
|
||||
#define LED0
|
||||
#define GPS
|
||||
#define LED_STRIP
|
||||
|
|
|
@ -86,9 +86,6 @@
|
|||
#define I2C2_SDA_PIN_SOURCE GPIO_PinSource10
|
||||
#define I2C2_SDA_CLK_SOURCE RCC_AHBPeriph_GPIOA
|
||||
|
||||
|
||||
#define SENSORS_SET (SENSOR_ACC | SENSOR_BARO | SENSOR_MAG)
|
||||
|
||||
#define BLACKBOX
|
||||
#define SERIAL_RX
|
||||
#define GPS
|
||||
|
|
|
@ -120,8 +120,6 @@
|
|||
#define WS2811_DMA_CHANNEL DMA1_Channel2
|
||||
#define WS2811_IRQ DMA1_Channel2_IRQn
|
||||
|
||||
#define SENSORS_SET (SENSOR_ACC | SENSOR_BARO | SENSOR_MAG)
|
||||
|
||||
#define GPS
|
||||
#define BLACKBOX
|
||||
#define TELEMETRY
|
||||
|
|
|
@ -81,8 +81,6 @@
|
|||
#define EXTERNAL1_ADC_GPIO_PIN GPIO_Pin_3
|
||||
#define EXTERNAL1_ADC_CHANNEL ADC_Channel_9
|
||||
|
||||
#define SENSORS_SET (SENSOR_ACC | SENSOR_MAG)
|
||||
|
||||
#define BLACKBOX
|
||||
#define GPS
|
||||
#define LED_STRIP
|
||||
|
|
Loading…
Reference in New Issue