Moved xx_hardware out of sensorSelectionConfig into config for specific sensor
This commit is contained in:
parent
60e2227396
commit
06e871406e
|
@ -1271,9 +1271,9 @@ static bool blackboxWriteSysinfo()
|
|||
BLACKBOX_PRINT_HEADER_LINE("gyro_notch_cutoff:%d,%d", gyroConfig()->gyro_soft_notch_cutoff_1,
|
||||
gyroConfig()->gyro_soft_notch_cutoff_2);
|
||||
BLACKBOX_PRINT_HEADER_LINE("acc_lpf_hz:%d", (int)(accelerometerConfig()->acc_lpf_hz * 100.0f));
|
||||
BLACKBOX_PRINT_HEADER_LINE("acc_hardware:%d", sensorSelectionConfig()->acc_hardware);
|
||||
BLACKBOX_PRINT_HEADER_LINE("baro_hardware:%d", sensorSelectionConfig()->baro_hardware);
|
||||
BLACKBOX_PRINT_HEADER_LINE("mag_hardware:%d", sensorSelectionConfig()->mag_hardware);
|
||||
BLACKBOX_PRINT_HEADER_LINE("acc_hardware:%d", accelerometerConfig()->acc_hardware);
|
||||
BLACKBOX_PRINT_HEADER_LINE("baro_hardware:%d", barometerConfig()->baro_hardware);
|
||||
BLACKBOX_PRINT_HEADER_LINE("mag_hardware:%d", compassConfig()->mag_hardware);
|
||||
BLACKBOX_PRINT_HEADER_LINE("gyro_cal_on_first_arm:%d", armingConfig()->gyro_cal_on_first_arm);
|
||||
BLACKBOX_PRINT_HEADER_LINE("rc_interpolation:%d", rxConfig()->rcInterpolation);
|
||||
BLACKBOX_PRINT_HEADER_LINE("rc_interpolation_interval:%d", rxConfig()->rcInterpolationInterval);
|
||||
|
|
|
@ -66,7 +66,6 @@
|
|||
#define servoConfig(x) (&masterConfig.servoConfig)
|
||||
#define servoMixerConfig(x) (&masterConfig.servoMixerConfig)
|
||||
#define gimbalConfig(x) (&masterConfig.gimbalConfig)
|
||||
#define sensorSelectionConfig(x) (&masterConfig.sensorSelectionConfig)
|
||||
#define sensorTrims(x) (&masterConfig.sensorTrims)
|
||||
#define boardAlignment(x) (&masterConfig.boardAlignment)
|
||||
#define imuConfig(x) (&masterConfig.imuConfig)
|
||||
|
@ -122,7 +121,6 @@ typedef struct master_s {
|
|||
#endif
|
||||
|
||||
// global sensor-related stuff
|
||||
sensorSelectionConfig_t sensorSelectionConfig;
|
||||
sensorTrims_t sensorTrims;
|
||||
boardAlignment_t boardAlignment;
|
||||
|
||||
|
|
|
@ -589,15 +589,15 @@ void createDefaultConfig(master_t *config)
|
|||
config->boardAlignment.rollDegrees = 0;
|
||||
config->boardAlignment.pitchDegrees = 0;
|
||||
config->boardAlignment.yawDegrees = 0;
|
||||
config->sensorSelectionConfig.acc_hardware = ACC_DEFAULT; // default/autodetect
|
||||
config->accelerometerConfig.acc_hardware = ACC_DEFAULT; // default/autodetect
|
||||
config->max_angle_inclination = 700; // 70 degrees
|
||||
config->rcControlsConfig.yaw_control_direction = 1;
|
||||
config->gyroConfig.gyroMovementCalibrationThreshold = 32;
|
||||
|
||||
// xxx_hardware: 0:default/autodetect, 1: disable
|
||||
config->sensorSelectionConfig.mag_hardware = 1;
|
||||
config->compassConfig.mag_hardware = 1;
|
||||
|
||||
config->sensorSelectionConfig.baro_hardware = 1;
|
||||
config->barometerConfig.baro_hardware = 1;
|
||||
|
||||
resetBatteryConfig(&config->batteryConfig);
|
||||
|
||||
|
|
|
@ -1125,9 +1125,9 @@ static bool mspFcProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst, mspPostProcessFn
|
|||
break;
|
||||
|
||||
case MSP_SENSOR_CONFIG:
|
||||
sbufWriteU8(dst, sensorSelectionConfig()->acc_hardware);
|
||||
sbufWriteU8(dst, sensorSelectionConfig()->baro_hardware);
|
||||
sbufWriteU8(dst, sensorSelectionConfig()->mag_hardware);
|
||||
sbufWriteU8(dst, accelerometerConfig()->acc_hardware);
|
||||
sbufWriteU8(dst, barometerConfig()->baro_hardware);
|
||||
sbufWriteU8(dst, compassConfig()->mag_hardware);
|
||||
break;
|
||||
|
||||
case MSP_REBOOT:
|
||||
|
@ -1487,9 +1487,9 @@ static mspResult_e mspFcProcessInCommand(uint8_t cmdMSP, sbuf_t *src)
|
|||
break;
|
||||
|
||||
case MSP_SET_SENSOR_CONFIG:
|
||||
sensorSelectionConfig()->acc_hardware = sbufReadU8(src);
|
||||
sensorSelectionConfig()->baro_hardware = sbufReadU8(src);
|
||||
sensorSelectionConfig()->mag_hardware = sbufReadU8(src);
|
||||
accelerometerConfig()->acc_hardware = sbufReadU8(src);
|
||||
barometerConfig()->baro_hardware = sbufReadU8(src);
|
||||
compassConfig()->mag_hardware = sbufReadU8(src);
|
||||
break;
|
||||
|
||||
case MSP_RESET_CONF:
|
||||
|
|
|
@ -869,7 +869,7 @@ const clivalue_t valueTable[] = {
|
|||
{ "rx_min_usec", VAR_UINT16 | MASTER_VALUE, &rxConfig()->rx_min_usec, .config.minmax = { PWM_PULSE_MIN, PWM_PULSE_MAX } },
|
||||
{ "rx_max_usec", VAR_UINT16 | MASTER_VALUE, &rxConfig()->rx_max_usec, .config.minmax = { PWM_PULSE_MIN, PWM_PULSE_MAX } },
|
||||
|
||||
{ "acc_hardware", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &sensorSelectionConfig()->acc_hardware, .config.lookup = { TABLE_ACC_HARDWARE } },
|
||||
{ "acc_hardware", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &accelerometerConfig()->acc_hardware, .config.lookup = { TABLE_ACC_HARDWARE } },
|
||||
{ "acc_lpf_hz", VAR_UINT16 | MASTER_VALUE, &accelerometerConfig()->acc_lpf_hz, .config.minmax = { 0, 400 } },
|
||||
{ "accxy_deadband", VAR_UINT8 | MASTER_VALUE, &imuConfig()->accDeadband.xy, .config.minmax = { 0, 100 } },
|
||||
{ "accz_deadband", VAR_UINT8 | MASTER_VALUE, &imuConfig()->accDeadband.z, .config.minmax = { 0, 100 } },
|
||||
|
@ -882,11 +882,11 @@ const clivalue_t valueTable[] = {
|
|||
{ "baro_noise_lpf", VAR_FLOAT | MASTER_VALUE, &barometerConfig()->baro_noise_lpf, .config.minmax = { 0 , 1 } },
|
||||
{ "baro_cf_vel", VAR_FLOAT | MASTER_VALUE, &barometerConfig()->baro_cf_vel, .config.minmax = { 0 , 1 } },
|
||||
{ "baro_cf_alt", VAR_FLOAT | MASTER_VALUE, &barometerConfig()->baro_cf_alt, .config.minmax = { 0 , 1 } },
|
||||
{ "baro_hardware", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &sensorSelectionConfig()->baro_hardware, .config.lookup = { TABLE_BARO_HARDWARE } },
|
||||
{ "baro_hardware", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &barometerConfig()->baro_hardware, .config.lookup = { TABLE_BARO_HARDWARE } },
|
||||
#endif
|
||||
|
||||
#ifdef MAG
|
||||
{ "mag_hardware", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &sensorSelectionConfig()->mag_hardware, .config.lookup = { TABLE_MAG_HARDWARE } },
|
||||
{ "mag_hardware", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &compassConfig()->mag_hardware, .config.lookup = { TABLE_MAG_HARDWARE } },
|
||||
{ "mag_declination", VAR_INT16 | MASTER_VALUE, &compassConfig()->mag_declination, .config.minmax = { -18000, 18000 } },
|
||||
#endif
|
||||
{ "dterm_lowpass_type", VAR_UINT8 | PROFILE_VALUE | MODE_LOOKUP, &masterConfig.profile[0].pidProfile.dterm_filter_type, .config.lookup = { TABLE_LOWPASS_TYPE } },
|
||||
|
|
|
@ -422,11 +422,7 @@ void init(void)
|
|||
#else
|
||||
const void *sonarConfig = NULL;
|
||||
#endif
|
||||
if (!sensorsAutodetect(sensorSelectionConfig(),
|
||||
gyroConfig(),
|
||||
accelerometerConfig(),
|
||||
compassConfig(),
|
||||
sonarConfig)) {
|
||||
if (!sensorsAutodetect(gyroConfig(), accelerometerConfig(), compassConfig(), barometerConfig(), sonarConfig)) {
|
||||
// if gyro was not detected due to whatever reason, we give up now.
|
||||
failureMode(FAILURE_MISSING_ACC);
|
||||
}
|
||||
|
|
|
@ -57,6 +57,7 @@ typedef union rollAndPitchTrims_u {
|
|||
typedef struct accelerometerConfig_s {
|
||||
uint16_t acc_lpf_hz; // cutoff frequency for the low pass filter used on the acc z-axis for althold in Hz
|
||||
sensor_align_e acc_align; // acc alignment
|
||||
uint8_t acc_hardware; // Which acc hardware to use on boards with more than one device
|
||||
} accelerometerConfig_t;
|
||||
|
||||
void accInit(uint32_t gyroTargetLooptime);
|
||||
|
|
|
@ -30,6 +30,7 @@ typedef enum {
|
|||
#define BARO_SAMPLE_COUNT_MAX 48
|
||||
|
||||
typedef struct barometerConfig_s {
|
||||
uint8_t baro_hardware; // Barometer hardware to use
|
||||
uint8_t baro_sample_count; // size of baro filter array
|
||||
float baro_noise_lpf; // additional LPF to reduce baro noise
|
||||
float baro_cf_vel; // apply Complimentary Filter to keep the calculated velocity based on baro velocity (i.e. near real velocity)
|
||||
|
|
|
@ -43,6 +43,7 @@ typedef struct compassConfig_s {
|
|||
int16_t mag_declination; // Get your magnetic decliniation from here : http://magnetic-declination.com/
|
||||
// For example, -6deg 37min, = -637 Japan, format is [sign]dddmm (degreesminutes) default is zero.
|
||||
sensor_align_e mag_align; // mag alignment
|
||||
uint8_t mag_hardware; // Which mag hardware to use on boards with more than one device
|
||||
} compassConfig_t;
|
||||
|
||||
void compassInit(void);
|
||||
|
|
|
@ -623,10 +623,10 @@ static bool detectSonar(void)
|
|||
}
|
||||
#endif
|
||||
|
||||
bool sensorsAutodetect(const sensorSelectionConfig_t *sensorSelectionConfig,
|
||||
const gyroConfig_t *gyroConfig,
|
||||
const accelerometerConfig_t *accConfig,
|
||||
bool sensorsAutodetect(const gyroConfig_t *gyroConfig,
|
||||
const accelerometerConfig_t *accelerometerConfig,
|
||||
const compassConfig_t *compassConfig,
|
||||
const barometerConfig_t *barometerConfig,
|
||||
const sonarConfig_t *sonarConfig)
|
||||
{
|
||||
memset(&acc, 0, sizeof(acc));
|
||||
|
@ -651,7 +651,7 @@ bool sensorsAutodetect(const sensorSelectionConfig_t *sensorSelectionConfig,
|
|||
gyro.dev.init(&gyro.dev); // driver initialisation
|
||||
gyroInit(gyroConfig); // sensor initialisation
|
||||
|
||||
if (detectAcc(sensorSelectionConfig->acc_hardware)) {
|
||||
if (detectAcc(accelerometerConfig->acc_hardware)) {
|
||||
acc.dev.acc_1G = 256; // set default
|
||||
acc.dev.init(&acc.dev); // driver initialisation
|
||||
accInit(gyro.targetLooptime); // sensor initialisation
|
||||
|
@ -661,7 +661,7 @@ bool sensorsAutodetect(const sensorSelectionConfig_t *sensorSelectionConfig,
|
|||
mag.magneticDeclination = 0.0f; // TODO investigate if this is actually needed if there is no mag sensor or if the value stored in the config should be used.
|
||||
#ifdef MAG
|
||||
// FIXME extract to a method to reduce dependencies, maybe move to sensors_compass.c
|
||||
if (detectMag(sensorSelectionConfig->mag_hardware)) {
|
||||
if (detectMag(compassConfig->mag_hardware)) {
|
||||
// calculate magnetic declination
|
||||
const int16_t deg = compassConfig->mag_declination / 100;
|
||||
const int16_t min = compassConfig->mag_declination % 100;
|
||||
|
@ -673,7 +673,9 @@ bool sensorsAutodetect(const sensorSelectionConfig_t *sensorSelectionConfig,
|
|||
#endif
|
||||
|
||||
#ifdef BARO
|
||||
detectBaro(sensorSelectionConfig->baro_hardware);
|
||||
detectBaro(barometerConfig->baro_hardware);
|
||||
#else
|
||||
UNUSED(barometerConfig);
|
||||
#endif
|
||||
|
||||
#ifdef SONAR
|
||||
|
@ -687,8 +689,8 @@ bool sensorsAutodetect(const sensorSelectionConfig_t *sensorSelectionConfig,
|
|||
if (gyroConfig->gyro_align != ALIGN_DEFAULT) {
|
||||
gyro.dev.gyroAlign = gyroConfig->gyro_align;
|
||||
}
|
||||
if (accConfig->acc_align != ALIGN_DEFAULT) {
|
||||
acc.dev.accAlign = accConfig->acc_align;
|
||||
if (accelerometerConfig->acc_align != ALIGN_DEFAULT) {
|
||||
acc.dev.accAlign = accelerometerConfig->acc_align;
|
||||
}
|
||||
if (compassConfig->mag_align != ALIGN_DEFAULT) {
|
||||
mag.dev.magAlign = compassConfig->mag_align;
|
||||
|
|
|
@ -17,12 +17,8 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
struct sensorAlignmentConfig_s;
|
||||
struct sensorSelectionConfig_s;
|
||||
struct gyroConfig_s;
|
||||
struct sonarConfig_s;
|
||||
bool sensorsAutodetect(const sensorSelectionConfig_t *sensorSelectionConfig,
|
||||
const gyroConfig_t *gyroConfig,
|
||||
bool sensorsAutodetect(const gyroConfig_t *gyroConfig,
|
||||
const accelerometerConfig_t *accConfig,
|
||||
const compassConfig_t *compassConfig,
|
||||
const barometerConfig_t *baroConfig,
|
||||
const sonarConfig_t *sonarConfig);
|
||||
|
|
|
@ -52,12 +52,6 @@ typedef enum {
|
|||
SENSOR_GPSMAG = 1 << 6
|
||||
} sensors_e;
|
||||
|
||||
typedef struct sensorSelectionConfig_s {
|
||||
uint8_t acc_hardware; // Which acc hardware to use on boards with more than one device
|
||||
uint8_t baro_hardware; // Barometer hardware to use
|
||||
uint8_t mag_hardware; // Which mag hardware to use on boards with more than one device
|
||||
} sensorSelectionConfig_t;
|
||||
|
||||
typedef struct sensorTrims_s {
|
||||
flightDynamicsTrims_t accZero;
|
||||
flightDynamicsTrims_t magZero;
|
||||
|
|
Loading…
Reference in New Issue