1
0
Fork 0
mirror of https://github.com/iNavFlight/inav.git synced 2025-07-25 17:25:18 +03:00

Rearranged sensor data into different structs

This commit is contained in:
Martin Budden 2016-12-09 16:46:42 +00:00
parent 8fb18056c5
commit ec70fcae49
30 changed files with 185 additions and 198 deletions

View file

@ -1114,11 +1114,11 @@ static void loadMainState(timeUs_t currentTimeUs)
} }
for (i = 0; i < XYZ_AXIS_COUNT; i++) { for (i = 0; i < XYZ_AXIS_COUNT; i++) {
blackboxCurrent->gyroADC[i] = gyroADC[i]; blackboxCurrent->gyroADC[i] = gyro.gyroADC[i];
} }
for (i = 0; i < XYZ_AXIS_COUNT; i++) { for (i = 0; i < XYZ_AXIS_COUNT; i++) {
blackboxCurrent->accADC[i] = accADC[i]; blackboxCurrent->accADC[i] = acc.accADC[i];
} }
blackboxCurrent->attitude[0] = attitude.values.roll; blackboxCurrent->attitude[0] = attitude.values.roll;
@ -1336,7 +1336,7 @@ static bool blackboxWriteSysinfo()
} }
); );
BLACKBOX_PRINT_HEADER_LINE("looptime:%d", gyro.dev.targetLooptime); BLACKBOX_PRINT_HEADER_LINE("looptime:%d", gyro.targetLooptime);
BLACKBOX_PRINT_HEADER_LINE("rcExpo:%d", masterConfig.controlRateProfiles[masterConfig.current_profile_index].rcExpo8); BLACKBOX_PRINT_HEADER_LINE("rcExpo:%d", masterConfig.controlRateProfiles[masterConfig.current_profile_index].rcExpo8);
BLACKBOX_PRINT_HEADER_LINE("rcYawExpo:%d", masterConfig.controlRateProfiles[masterConfig.current_profile_index].rcYawExpo8); BLACKBOX_PRINT_HEADER_LINE("rcYawExpo:%d", masterConfig.controlRateProfiles[masterConfig.current_profile_index].rcYawExpo8);
BLACKBOX_PRINT_HEADER_LINE("thrMid:%d", masterConfig.controlRateProfiles[masterConfig.current_profile_index].thrMid8); BLACKBOX_PRINT_HEADER_LINE("thrMid:%d", masterConfig.controlRateProfiles[masterConfig.current_profile_index].thrMid8);
@ -1382,9 +1382,9 @@ static bool blackboxWriteSysinfo()
BLACKBOX_PRINT_HEADER_LINE("gyro_lpf:%d", masterConfig.gyroConfig.gyro_lpf); BLACKBOX_PRINT_HEADER_LINE("gyro_lpf:%d", masterConfig.gyroConfig.gyro_lpf);
BLACKBOX_PRINT_HEADER_LINE("gyro_lowpass_hz:%d", (int)(masterConfig.profile[masterConfig.current_profile_index].pidProfile.gyro_soft_lpf_hz * 100.0f)); BLACKBOX_PRINT_HEADER_LINE("gyro_lowpass_hz:%d", (int)(masterConfig.profile[masterConfig.current_profile_index].pidProfile.gyro_soft_lpf_hz * 100.0f));
BLACKBOX_PRINT_HEADER_LINE("acc_lpf_hz:%d", (int)(masterConfig.profile[masterConfig.current_profile_index].pidProfile.acc_soft_lpf_hz * 100.0f)); BLACKBOX_PRINT_HEADER_LINE("acc_lpf_hz:%d", (int)(masterConfig.profile[masterConfig.current_profile_index].pidProfile.acc_soft_lpf_hz * 100.0f));
BLACKBOX_PRINT_HEADER_LINE("acc_hardware:%d", masterConfig.sensorSelectionConfig.acc_hardware); BLACKBOX_PRINT_HEADER_LINE("acc_hardware:%d", masterConfig.accelerometerConfig.acc_hardware);
BLACKBOX_PRINT_HEADER_LINE("baro_hardware:%d", masterConfig.sensorSelectionConfig.baro_hardware); BLACKBOX_PRINT_HEADER_LINE("baro_hardware:%d", masterConfig.barometerConfig.baro_hardware);
BLACKBOX_PRINT_HEADER_LINE("mag_hardware:%d", masterConfig.sensorSelectionConfig.mag_hardware); BLACKBOX_PRINT_HEADER_LINE("mag_hardware:%d", masterConfig.compassConfig.mag_hardware);
BLACKBOX_PRINT_HEADER_LINE("features:%d", masterConfig.enabledFeatures); BLACKBOX_PRINT_HEADER_LINE("features:%d", masterConfig.enabledFeatures);
default: default:

View file

@ -623,7 +623,7 @@ bool blackboxDeviceOpen(void)
* = floor((looptime_ns * 3) / 500.0) * = floor((looptime_ns * 3) / 500.0)
* = (looptime_ns * 3) / 500 * = (looptime_ns * 3) / 500
*/ */
blackboxMaxHeaderBytesPerIteration = constrain((gyro.dev.targetLooptime * 3) / 500, 1, BLACKBOX_TARGET_HEADER_BUDGET_PER_ITERATION); blackboxMaxHeaderBytesPerIteration = constrain((gyro.targetLooptime * 3) / 500, 1, BLACKBOX_TARGET_HEADER_BUDGET_PER_ITERATION);
return blackboxPort != NULL; return blackboxPort != NULL;
} }

View file

@ -251,13 +251,6 @@ void resetPitotmeterConfig(pitotmeterConfig_t *pitotmeterConfig)
pitotmeterConfig->pitot_scale = 1.00f; pitotmeterConfig->pitot_scale = 1.00f;
} }
void resetSensorAlignment(sensorAlignmentConfig_t *sensorAlignmentConfig)
{
sensorAlignmentConfig->gyro_align = ALIGN_DEFAULT;
sensorAlignmentConfig->acc_align = ALIGN_DEFAULT;
sensorAlignmentConfig->mag_align = ALIGN_DEFAULT;
}
void resetMotorConfig(motorConfig_t *motorConfig) void resetMotorConfig(motorConfig_t *motorConfig)
{ {
#ifdef BRUSHED_MOTORS #ifdef BRUSHED_MOTORS
@ -407,7 +400,7 @@ uint32_t getPidUpdateRate(void) {
} }
uint32_t getGyroUpdateRate(void) { uint32_t getGyroUpdateRate(void) {
return gyro.dev.targetLooptime; return gyro.targetLooptime;
} }
uint16_t getAccUpdateRate(void) { uint16_t getAccUpdateRate(void) {
@ -500,16 +493,18 @@ static void resetConf(void)
resetAccelerometerTrims(&masterConfig.sensorTrims.accZero, &masterConfig.sensorTrims.accGain); resetAccelerometerTrims(&masterConfig.sensorTrims.accZero, &masterConfig.sensorTrims.accGain);
resetSensorAlignment(&masterConfig.sensorAlignmentConfig); masterConfig.gyroConfig.gyro_align = ALIGN_DEFAULT;
masterConfig.accelerometerConfig.acc_align = ALIGN_DEFAULT;
masterConfig.compassConfig.mag_align = ALIGN_DEFAULT;
masterConfig.boardAlignment.rollDeciDegrees = 0; masterConfig.boardAlignment.rollDeciDegrees = 0;
masterConfig.boardAlignment.pitchDeciDegrees = 0; masterConfig.boardAlignment.pitchDeciDegrees = 0;
masterConfig.boardAlignment.yawDeciDegrees = 0; masterConfig.boardAlignment.yawDeciDegrees = 0;
masterConfig.sensorSelectionConfig.acc_hardware = ACC_DEFAULT; // default/autodetect masterConfig.accelerometerConfig.acc_hardware = ACC_DEFAULT; // default/autodetect
masterConfig.gyroConfig.gyroMovementCalibrationThreshold = 32; masterConfig.gyroConfig.gyroMovementCalibrationThreshold = 32;
masterConfig.sensorSelectionConfig.mag_hardware = MAG_DEFAULT; // default/autodetect masterConfig.compassConfig.mag_hardware = MAG_DEFAULT; // default/autodetect
masterConfig.sensorSelectionConfig.baro_hardware = BARO_DEFAULT; // default/autodetect masterConfig.barometerConfig.baro_hardware = BARO_DEFAULT; // default/autodetect
resetBatteryConfig(&masterConfig.batteryConfig); resetBatteryConfig(&masterConfig.batteryConfig);
@ -590,7 +585,7 @@ static void resetConf(void)
// for (int i = 0; i < CHECKBOXITEMS; i++) // for (int i = 0; i < CHECKBOXITEMS; i++)
// cfg.activate[i] = 0; // cfg.activate[i] = 0;
currentProfile->mag_declination = 0; masterConfig.compassConfig.mag_declination = 0;
currentProfile->modeActivationOperator = MODE_OPERATOR_OR; // default is to OR multiple-channel mode activation conditions currentProfile->modeActivationOperator = MODE_OPERATOR_OR; // default is to OR multiple-channel mode activation conditions

View file

@ -56,6 +56,7 @@
#include "sensors/boardalignment.h" #include "sensors/boardalignment.h"
#include "sensors/barometer.h" #include "sensors/barometer.h"
#include "sensors/battery.h" #include "sensors/battery.h"
#include "sensors/compass.h"
#include "sensors/gyro.h" #include "sensors/gyro.h"
#include "sensors/pitotmeter.h" #include "sensors/pitotmeter.h"
@ -93,8 +94,6 @@ typedef struct master_s {
#endif #endif
// global sensor-related stuff // global sensor-related stuff
sensorSelectionConfig_t sensorSelectionConfig;
sensorAlignmentConfig_t sensorAlignmentConfig;
sensorTrims_t sensorTrims; sensorTrims_t sensorTrims;
boardAlignment_t boardAlignment; boardAlignment_t boardAlignment;
@ -102,8 +101,12 @@ typedef struct master_s {
gyroConfig_t gyroConfig; gyroConfig_t gyroConfig;
accelerometerConfig_t accelerometerConfig;
barometerConfig_t barometerConfig; barometerConfig_t barometerConfig;
compassConfig_t compassConfig;
pitotmeterConfig_t pitotmeterConfig; pitotmeterConfig_t pitotmeterConfig;
batteryConfig_t batteryConfig; batteryConfig_t batteryConfig;

View file

@ -28,9 +28,6 @@ typedef struct profile_s {
uint8_t defaultRateProfileIndex; uint8_t defaultRateProfileIndex;
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.
modeActivationCondition_t modeActivationConditions[MAX_MODE_ACTIVATION_CONDITION_COUNT]; modeActivationCondition_t modeActivationConditions[MAX_MODE_ACTIVATION_CONDITION_COUNT];
modeActivationOperator_e modeActivationOperator; modeActivationOperator_e modeActivationOperator;

View file

@ -39,10 +39,10 @@ typedef struct gyroDev_s {
sensorReadFuncPtr temperature; // read temperature if available sensorReadFuncPtr temperature; // read temperature if available
sensorGyroInterruptStatusFuncPtr intStatus; sensorGyroInterruptStatusFuncPtr intStatus;
float scale; // scalefactor float scale; // scalefactor
uint32_t targetLooptime;
volatile bool dataReady; volatile bool dataReady;
uint16_t lpf; uint16_t lpf;
int16_t gyroADCRaw[XYZ_AXIS_COUNT]; int16_t gyroADCRaw[XYZ_AXIS_COUNT];
sensor_align_e gyroAlign;
} gyroDev_t; } gyroDev_t;
typedef struct accDev_s { typedef struct accDev_s {
@ -50,4 +50,5 @@ typedef struct accDev_s {
sensorReadFuncPtr read; // read 3 axis data function sensorReadFuncPtr read; // read 3 axis data function
uint16_t acc_1G; uint16_t acc_1G;
char revisionCode; // a revision code for the sensor, if known char revisionCode; // a revision code for the sensor, if known
sensor_align_e accAlign;
} accDev_t; } accDev_t;

View file

@ -22,6 +22,7 @@
typedef struct magDev_s { typedef struct magDev_s {
sensorInitFuncPtr init; // initialize function sensorInitFuncPtr init; // initialize function
sensorReadFuncPtr read; // read 3 axis data function sensorReadFuncPtr read; // read 3 axis data function
sensor_align_e magAlign;
} magDev_t; } magDev_t;
#ifndef MAG_I2C_INSTANCE #ifndef MAG_I2C_INSTANCE

View file

@ -17,6 +17,18 @@
#pragma once #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;
struct accDev_s; struct accDev_s;
typedef bool (*sensorInitFuncPtr)(void); // sensor init prototype typedef bool (*sensorInitFuncPtr)(void); // sensor init prototype
typedef bool (*sensorReadFuncPtr)(int16_t *data); // sensor read and align prototype typedef bool (*sensorReadFuncPtr)(int16_t *data); // sensor read and align prototype

View file

@ -99,6 +99,7 @@
#include "sensors/gyro.h" #include "sensors/gyro.h"
#include "sensors/battery.h" #include "sensors/battery.h"
#include "sensors/boardalignment.h" #include "sensors/boardalignment.h"
#include "sensors/pitotmeter.h"
#include "sensors/initialisation.h" #include "sensors/initialisation.h"
#include "sensors/sonar.h" #include "sensors/sonar.h"
@ -479,10 +480,13 @@ void init(void)
} }
#endif #endif
if (!sensorsAutodetect(&masterConfig.sensorAlignmentConfig, if (!sensorsAutodetect(
&masterConfig.sensorSelectionConfig, &masterConfig.gyroConfig,
currentProfile->mag_declination, &masterConfig.accelerometerConfig,
&masterConfig.gyroConfig)) { &masterConfig.compassConfig,
&masterConfig.barometerConfig,
&masterConfig.pitotmeterConfig
)) {
// if gyro was not detected due to whatever reason, we give up now. // if gyro was not detected due to whatever reason, we give up now.
failureMode(FAILURE_MISSING_ACC); failureMode(FAILURE_MISSING_ACC);

View file

@ -539,10 +539,10 @@ static bool mspFcProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst, mspPostProcessFn
// Hack scale due to choice of units for sensor data in multiwii // Hack scale due to choice of units for sensor data in multiwii
const uint8_t scale = (acc.dev.acc_1G > 1024) ? 8 : 1; const uint8_t scale = (acc.dev.acc_1G > 1024) ? 8 : 1;
for (int i = 0; i < 3; i++) { for (int i = 0; i < 3; i++) {
sbufWriteU16(dst, accADC[i] / scale); sbufWriteU16(dst, acc.accADC[i] / scale);
} }
for (int i = 0; i < 3; i++) { for (int i = 0; i < 3; i++) {
sbufWriteU16(dst, gyroADC[i]); sbufWriteU16(dst, gyro.gyroADC[i]);
} }
for (int i = 0; i < 3; i++) { for (int i = 0; i < 3; i++) {
sbufWriteU16(dst, mag.magADC[i]); sbufWriteU16(dst, mag.magADC[i]);
@ -725,7 +725,7 @@ static bool mspFcProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst, mspPostProcessFn
sbufWriteU8(dst, masterConfig.rxConfig.rssi_channel); sbufWriteU8(dst, masterConfig.rxConfig.rssi_channel);
sbufWriteU8(dst, 0); sbufWriteU8(dst, 0);
sbufWriteU16(dst, currentProfile->mag_declination / 10); sbufWriteU16(dst, masterConfig.compassConfig.mag_declination / 10);
sbufWriteU8(dst, masterConfig.batteryConfig.vbatscale); sbufWriteU8(dst, masterConfig.batteryConfig.vbatscale);
sbufWriteU8(dst, masterConfig.batteryConfig.vbatmincellvoltage); sbufWriteU8(dst, masterConfig.batteryConfig.vbatmincellvoltage);
@ -996,9 +996,9 @@ static bool mspFcProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst, mspPostProcessFn
break; break;
case MSP_SENSOR_ALIGNMENT: case MSP_SENSOR_ALIGNMENT:
sbufWriteU8(dst, masterConfig.sensorAlignmentConfig.gyro_align); sbufWriteU8(dst, masterConfig.gyroConfig.gyro_align);
sbufWriteU8(dst, masterConfig.sensorAlignmentConfig.acc_align); sbufWriteU8(dst, masterConfig.accelerometerConfig.acc_align);
sbufWriteU8(dst, masterConfig.sensorAlignmentConfig.mag_align); sbufWriteU8(dst, masterConfig.compassConfig.mag_align);
break; break;
case MSP_ADVANCED_CONFIG: case MSP_ADVANCED_CONFIG:
@ -1302,7 +1302,7 @@ static mspResult_e mspFcProcessInCommand(uint8_t cmdMSP, sbuf_t *src)
masterConfig.rxConfig.rssi_channel = sbufReadU8(src); masterConfig.rxConfig.rssi_channel = sbufReadU8(src);
sbufReadU8(src); sbufReadU8(src);
currentProfile->mag_declination = sbufReadU16(src) * 10; masterConfig.compassConfig.mag_declination = sbufReadU16(src) * 10;
masterConfig.batteryConfig.vbatscale = sbufReadU8(src); // actual vbatscale as intended masterConfig.batteryConfig.vbatscale = sbufReadU8(src); // actual vbatscale as intended
masterConfig.batteryConfig.vbatmincellvoltage = sbufReadU8(src); // vbatlevel_warn1 in MWC2.3 GUI masterConfig.batteryConfig.vbatmincellvoltage = sbufReadU8(src); // vbatlevel_warn1 in MWC2.3 GUI
@ -1377,9 +1377,9 @@ static mspResult_e mspFcProcessInCommand(uint8_t cmdMSP, sbuf_t *src)
break; break;
case MSP_SET_SENSOR_ALIGNMENT: case MSP_SET_SENSOR_ALIGNMENT:
masterConfig.sensorAlignmentConfig.gyro_align = sbufReadU8(src); masterConfig.gyroConfig.gyro_align = sbufReadU8(src);
masterConfig.sensorAlignmentConfig.acc_align = sbufReadU8(src); masterConfig.accelerometerConfig.acc_align = sbufReadU8(src);
masterConfig.sensorAlignmentConfig.mag_align = sbufReadU8(src); masterConfig.compassConfig.mag_align = sbufReadU8(src);
break; break;
case MSP_SET_ADVANCED_CONFIG: case MSP_SET_ADVANCED_CONFIG:

View file

@ -274,7 +274,7 @@ void fcTasksInit(void)
} }
#else #else
rescheduleTask(TASK_GYROPID, gyro.dev.targetLooptime); rescheduleTask(TASK_GYROPID, gyro.targetLooptime);
setTaskEnabled(TASK_GYROPID, true); setTaskEnabled(TASK_GYROPID, true);
#endif #endif

View file

@ -485,7 +485,7 @@ void filterRc(bool isRXDataNew)
#ifdef ASYNC_GYRO_PROCESSING #ifdef ASYNC_GYRO_PROCESSING
biquadFilterInitLPF(&filteredCycleTimeState, 1, getPidUpdateRate()); biquadFilterInitLPF(&filteredCycleTimeState, 1, getPidUpdateRate());
#else #else
biquadFilterInitLPF(&filteredCycleTimeState, 1, gyro.dev.targetLooptime); biquadFilterInitLPF(&filteredCycleTimeState, 1, gyro.targetLooptime);
#endif #endif
filterInitialised = true; filterInitialised = true;
} }
@ -525,7 +525,7 @@ void taskGyro(timeUs_t currentTimeUs) {
#ifdef ASYNC_GYRO_PROCESSING #ifdef ASYNC_GYRO_PROCESSING
if (gyroSyncCheckUpdate(&gyro.dev) || ((currentDeltaTime + (micros() - currentTimeUs)) >= (getGyroUpdateRate() + GYRO_WATCHDOG_DELAY))) { if (gyroSyncCheckUpdate(&gyro.dev) || ((currentDeltaTime + (micros() - currentTimeUs)) >= (getGyroUpdateRate() + GYRO_WATCHDOG_DELAY))) {
#else #else
if (gyroSyncCheckUpdate(&gyro.dev) || ((currentDeltaTime + (micros() - currentTimeUs)) >= (gyro.dev.targetLooptime + GYRO_WATCHDOG_DELAY))) { if (gyroSyncCheckUpdate(&gyro.dev) || ((currentDeltaTime + (micros() - currentTimeUs)) >= (gyro.targetLooptime + GYRO_WATCHDOG_DELAY))) {
#endif #endif
break; break;
} }

View file

@ -105,7 +105,7 @@ void imuUpdateGyroscope(uint32_t gyroUpdateDeltaUs)
const float gyroUpdateDelta = gyroUpdateDeltaUs * 1e-6f; const float gyroUpdateDelta = gyroUpdateDeltaUs * 1e-6f;
for (int axis = 0; axis < 3; axis++) { for (int axis = 0; axis < 3; axis++) {
imuAccumulatedRate[axis] += gyroADC[axis] * gyroScale * gyroUpdateDelta; imuAccumulatedRate[axis] += gyro.gyroADC[axis] * gyroScale * gyroUpdateDelta;
} }
imuAccumulatedRateTime += gyroUpdateDelta; imuAccumulatedRateTime += gyroUpdateDelta;
@ -412,7 +412,7 @@ static int imuCalculateAccelerometerConfidence(void)
int32_t accMagnitude = 0; int32_t accMagnitude = 0;
for (axis = 0; axis < 3; axis++) { for (axis = 0; axis < 3; axis++) {
accMagnitude += (int32_t)accADC[axis] * accADC[axis]; accMagnitude += (int32_t)acc.accADC[axis] * acc.accADC[axis];
} }
// Magnitude^2 in percent of G^2 // Magnitude^2 in percent of G^2
@ -572,7 +572,7 @@ void imuUpdateAccelerometer(void)
#ifdef ASYNC_GYRO_PROCESSING #ifdef ASYNC_GYRO_PROCESSING
for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) { for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) {
imuAccumulatedAcc[axis] += accADC[axis] * (GRAVITY_CMSS / acc.dev.acc_1G); imuAccumulatedAcc[axis] += acc.accADC[axis] * (GRAVITY_CMSS / acc.dev.acc_1G);
} }
imuAccumulatedAccCount++; imuAccumulatedAccCount++;
#endif #endif
@ -602,9 +602,9 @@ void imuUpdateAttitude(timeUs_t currentTimeUs)
imuCalculateEstimatedAttitude(dT); // Update attitude estimate imuCalculateEstimatedAttitude(dT); // Update attitude estimate
#endif #endif
} else { } else {
accADC[X] = 0; acc.accADC[X] = 0;
accADC[Y] = 0; acc.accADC[Y] = 0;
accADC[Z] = 0; acc.accADC[Z] = 0;
} }
} }

View file

@ -519,7 +519,7 @@ void pidController(const pidProfile_t *pidProfile, const controlRateConfig_t *co
for (int axis = 0; axis < 3; axis++) { for (int axis = 0; axis < 3; axis++) {
// Step 1: Calculate gyro rates // Step 1: Calculate gyro rates
pidState[axis].gyroRate = gyroADC[axis] * gyro.dev.scale; pidState[axis].gyroRate = gyro.gyroADC[axis] * gyro.dev.scale;
// Step 2: Read target // Step 2: Read target
float rateTarget; float rateTarget;

View file

@ -446,7 +446,7 @@ void filterServos(void)
// Initialize servo lowpass filter (servos are calculated at looptime rate) // Initialize servo lowpass filter (servos are calculated at looptime rate)
if (!servoFilterIsSet) { if (!servoFilterIsSet) {
for (servoIdx = 0; servoIdx < MAX_SUPPORTED_SERVOS; servoIdx++) { for (servoIdx = 0; servoIdx < MAX_SUPPORTED_SERVOS; servoIdx++) {
biquadFilterInitLPF(&servoFitlerState[servoIdx], servoMixerConfig->servo_lowpass_freq, gyro.dev.targetLooptime); biquadFilterInitLPF(&servoFitlerState[servoIdx], servoMixerConfig->servo_lowpass_freq, gyro.targetLooptime);
} }
servoFilterIsSet = true; servoFilterIsSet = true;

View file

@ -787,9 +787,9 @@ const clivalue_t valueTable[] = {
{ "multiwii_current_meter_output", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.batteryConfig.multiwiiCurrentMeterOutput, .config.lookup = { TABLE_OFF_ON }, 0 }, { "multiwii_current_meter_output", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.batteryConfig.multiwiiCurrentMeterOutput, .config.lookup = { TABLE_OFF_ON }, 0 },
{ "current_meter_type", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.batteryConfig.currentMeterType, .config.lookup = { TABLE_CURRENT_SENSOR }, 0 }, { "current_meter_type", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.batteryConfig.currentMeterType, .config.lookup = { TABLE_CURRENT_SENSOR }, 0 },
{ "align_gyro", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.sensorAlignmentConfig.gyro_align, .config.lookup = { TABLE_ALIGNMENT }, 0 }, { "align_gyro", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.gyroConfig.gyro_align, .config.lookup = { TABLE_ALIGNMENT }, 0 },
{ "align_acc", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.sensorAlignmentConfig.acc_align, .config.lookup = { TABLE_ALIGNMENT }, 0 }, { "align_acc", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.accelerometerConfig.acc_align, .config.lookup = { TABLE_ALIGNMENT }, 0 },
{ "align_mag", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.sensorAlignmentConfig.mag_align, .config.lookup = { TABLE_ALIGNMENT }, 0 }, { "align_mag", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.compassConfig.mag_align, .config.lookup = { TABLE_ALIGNMENT }, 0 },
{ "align_board_roll", VAR_INT16 | MASTER_VALUE, &masterConfig.boardAlignment.rollDeciDegrees, .config.minmax = { -1800, 3600 }, 0 }, { "align_board_roll", VAR_INT16 | MASTER_VALUE, &masterConfig.boardAlignment.rollDeciDegrees, .config.minmax = { -1800, 3600 }, 0 },
{ "align_board_pitch", VAR_INT16 | MASTER_VALUE, &masterConfig.boardAlignment.pitchDeciDegrees, .config.minmax = { -1800, 3600 }, 0 }, { "align_board_pitch", VAR_INT16 | MASTER_VALUE, &masterConfig.boardAlignment.pitchDeciDegrees, .config.minmax = { -1800, 3600 }, 0 },
@ -853,23 +853,23 @@ const clivalue_t valueTable[] = {
{ "rx_min_usec", VAR_UINT16 | MASTER_VALUE, &masterConfig.rxConfig.rx_min_usec, .config.minmax = { PWM_PULSE_MIN, PWM_PULSE_MAX }, 0 }, { "rx_min_usec", VAR_UINT16 | MASTER_VALUE, &masterConfig.rxConfig.rx_min_usec, .config.minmax = { PWM_PULSE_MIN, PWM_PULSE_MAX }, 0 },
{ "rx_max_usec", VAR_UINT16 | MASTER_VALUE, &masterConfig.rxConfig.rx_max_usec, .config.minmax = { PWM_PULSE_MIN, PWM_PULSE_MAX }, 0 }, { "rx_max_usec", VAR_UINT16 | MASTER_VALUE, &masterConfig.rxConfig.rx_max_usec, .config.minmax = { PWM_PULSE_MIN, PWM_PULSE_MAX }, 0 },
{ "acc_hardware", VAR_UINT8 | MASTER_VALUE, &masterConfig.sensorSelectionConfig.acc_hardware, .config.minmax = { 0, ACC_MAX }, 0 }, { "acc_hardware", VAR_UINT8 | MASTER_VALUE, &masterConfig.accelerometerConfig.acc_hardware, .config.minmax = { 0, ACC_MAX }, 0 },
#ifdef BARO #ifdef BARO
{ "baro_use_median_filter", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.barometerConfig.use_median_filtering, .config.lookup = { TABLE_OFF_ON }, 0 }, { "baro_use_median_filter", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.barometerConfig.use_median_filtering, .config.lookup = { TABLE_OFF_ON }, 0 },
{ "baro_hardware", VAR_UINT8 | MASTER_VALUE, &masterConfig.sensorSelectionConfig.baro_hardware, .config.minmax = { 0, BARO_MAX }, 0 }, { "baro_hardware", VAR_UINT8 | MASTER_VALUE, &masterConfig.barometerConfig.baro_hardware, .config.minmax = { 0, BARO_MAX }, 0 },
#endif #endif
#ifdef PITOT #ifdef PITOT
{ "pitot_hardware", VAR_UINT8 | MASTER_VALUE, &masterConfig.sensorSelectionConfig.pitot_hardware, .config.minmax = { 0, PITOT_MAX }, 0 }, { "pitot_hardware", VAR_UINT8 | MASTER_VALUE, &masterConfig.pitotmeterConfig.pitot_hardware, .config.minmax = { 0, PITOT_MAX }, 0 },
{ "pitot_use_median_filter", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.pitotmeterConfig.use_median_filtering, .config.lookup = { TABLE_OFF_ON }, 0 }, { "pitot_use_median_filter", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.pitotmeterConfig.use_median_filtering, .config.lookup = { TABLE_OFF_ON }, 0 },
{ "pitot_noise_lpf", VAR_FLOAT | MASTER_VALUE, &masterConfig.pitotmeterConfig.pitot_noise_lpf, .config.minmax = { 0, 1 }, 0 }, { "pitot_noise_lpf", VAR_FLOAT | MASTER_VALUE, &masterConfig.pitotmeterConfig.pitot_noise_lpf, .config.minmax = { 0, 1 }, 0 },
{ "pitot_scale", VAR_FLOAT | MASTER_VALUE, &masterConfig.pitotmeterConfig.pitot_scale, .config.minmax = { 0, 100 }, 0 }, { "pitot_scale", VAR_FLOAT | MASTER_VALUE, &masterConfig.pitotmeterConfig.pitot_scale, .config.minmax = { 0, 100 }, 0 },
#endif #endif
#ifdef MAG #ifdef MAG
{ "mag_hardware", VAR_UINT8 | MASTER_VALUE, &masterConfig.sensorSelectionConfig.mag_hardware, .config.minmax = { 0, MAG_MAX }, 0 }, { "mag_hardware", VAR_UINT8 | MASTER_VALUE, &masterConfig.compassConfig.mag_hardware, .config.minmax = { 0, MAG_MAX }, 0 },
{ "mag_declination", VAR_INT16 | PROFILE_VALUE, &masterConfig.profile[0].mag_declination, .config.minmax = { -18000, 18000 }, 0 }, { "mag_declination", VAR_INT16 | PROFILE_VALUE, &masterConfig.compassConfig.mag_declination, .config.minmax = { -18000, 18000 }, 0 },
{ "mag_hold_rate_limit", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.mag_hold_rate_limit, .config.minmax = { MAG_HOLD_RATE_LIMIT_MIN, MAG_HOLD_RATE_LIMIT_MAX }, 0 }, { "mag_hold_rate_limit", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.mag_hold_rate_limit, .config.minmax = { MAG_HOLD_RATE_LIMIT_MIN, MAG_HOLD_RATE_LIMIT_MAX }, 0 },
#endif #endif

View file

@ -38,9 +38,6 @@
#include "sensors/acceleration.h" #include "sensors/acceleration.h"
acc_t acc; // acc access functions acc_t acc; // acc access functions
int32_t accADC[XYZ_AXIS_COUNT];
sensor_align_e accAlign = 0;
uint32_t accTargetLooptime;
static uint16_t calibratingA = 0; // the calibration is done is the main loop. Calibrating decreases at each cycle down to 0, then we enter in a normal mode. static uint16_t calibratingA = 0; // the calibration is done is the main loop. Calibrating decreases at each cycle down to 0, then we enter in a normal mode.
static int16_t accADCRaw[XYZ_AXIS_COUNT]; static int16_t accADCRaw[XYZ_AXIS_COUNT];
@ -55,10 +52,10 @@ void accInit(uint32_t targetLooptime)
{ {
acc.dev.acc_1G = 256; // set default acc.dev.acc_1G = 256; // set default
acc.dev.init(&acc.dev); acc.dev.init(&acc.dev);
accTargetLooptime = targetLooptime; acc.accTargetLooptime = targetLooptime;
if (accLpfCutHz) { if (accLpfCutHz) {
for (int axis = 0; axis < 3; axis++) { for (int axis = 0; axis < 3; axis++) {
biquadFilterInitLPF(&accFilter[axis], accLpfCutHz, accTargetLooptime); biquadFilterInitLPF(&accFilter[axis], accLpfCutHz, acc.accTargetLooptime);
} }
} }
} }
@ -108,7 +105,7 @@ int getPrimaryAxisIndex(int32_t sample[3])
void performAcclerationCalibration(void) void performAcclerationCalibration(void)
{ {
int axisIndex = getPrimaryAxisIndex(accADC); int axisIndex = getPrimaryAxisIndex(acc.accADC);
// Check if sample is usable // Check if sample is usable
if (axisIndex < 0) { if (axisIndex < 0) {
@ -129,10 +126,10 @@ void performAcclerationCalibration(void)
} }
if (!calibratedAxis[axisIndex]) { if (!calibratedAxis[axisIndex]) {
sensorCalibrationPushSampleForOffsetCalculation(&calState, accADC); sensorCalibrationPushSampleForOffsetCalculation(&calState, acc.accADC);
accSamples[axisIndex][X] += accADC[X]; accSamples[axisIndex][X] += acc.accADC[X];
accSamples[axisIndex][Y] += accADC[Y]; accSamples[axisIndex][Y] += acc.accADC[Y];
accSamples[axisIndex][Z] += accADC[Z]; accSamples[axisIndex][Z] += acc.accADC[Z];
if (isOnFinalAccelerationCalibrationCycle()) { if (isOnFinalAccelerationCalibrationCycle()) {
calibratedAxis[axisIndex] = true; calibratedAxis[axisIndex] = true;
@ -178,9 +175,9 @@ void performAcclerationCalibration(void)
static void applyAccelerationZero(const flightDynamicsTrims_t * accZero, const flightDynamicsTrims_t * accGain) static void applyAccelerationZero(const flightDynamicsTrims_t * accZero, const flightDynamicsTrims_t * accGain)
{ {
accADC[X] = (accADC[X] - accZero->raw[X]) * accGain->raw[X] / 4096; acc.accADC[X] = (acc.accADC[X] - accZero->raw[X]) * accGain->raw[X] / 4096;
accADC[Y] = (accADC[Y] - accZero->raw[Y]) * accGain->raw[Y] / 4096; acc.accADC[Y] = (acc.accADC[Y] - accZero->raw[Y]) * accGain->raw[Y] / 4096;
accADC[Z] = (accADC[Z] - accZero->raw[Z]) * accGain->raw[Z] / 4096; acc.accADC[Z] = (acc.accADC[Z] - accZero->raw[Z]) * accGain->raw[Z] / 4096;
} }
void updateAccelerationReadings(void) void updateAccelerationReadings(void)
@ -190,12 +187,12 @@ void updateAccelerationReadings(void)
} }
for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) { for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) {
accADC[axis] = accADCRaw[axis]; acc.accADC[axis] = accADCRaw[axis];
} }
if (accLpfCutHz) { if (accLpfCutHz) {
for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) { for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) {
accADC[axis] = lrintf(biquadFilterApply(&accFilter[axis], (float) accADC[axis])); acc.accADC[axis] = lrintf(biquadFilterApply(&accFilter[axis], (float)acc.accADC[axis]));
} }
} }
@ -205,7 +202,7 @@ void updateAccelerationReadings(void)
applyAccelerationZero(accZero, accGain); applyAccelerationZero(accZero, accGain);
alignSensors(accADC, accAlign); alignSensors(acc.accADC, acc.dev.accAlign);
} }
void setAccelerationZero(flightDynamicsTrims_t * accZeroToUse) void setAccelerationZero(flightDynamicsTrims_t * accZeroToUse)
@ -221,9 +218,9 @@ void setAccelerationGain(flightDynamicsTrims_t * accGainToUse)
void setAccelerationFilter(uint8_t initialAccLpfCutHz) void setAccelerationFilter(uint8_t initialAccLpfCutHz)
{ {
accLpfCutHz = initialAccLpfCutHz; accLpfCutHz = initialAccLpfCutHz;
if (accTargetLooptime) { if (acc.accTargetLooptime) {
for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) { for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) {
biquadFilterInitLPF(&accFilter[axis], accLpfCutHz, accTargetLooptime); biquadFilterInitLPF(&accFilter[axis], accLpfCutHz, acc.accTargetLooptime);
} }
} }
} }

View file

@ -17,8 +17,8 @@
#pragma once #pragma once
#include "common/axis.h"
#include "drivers/accgyro.h" #include "drivers/accgyro.h"
#include "sensors/sensors.h" #include "sensors/sensors.h"
// Type of accelerometer used/detected // Type of accelerometer used/detected
@ -39,12 +39,16 @@ typedef enum {
typedef struct acc_s { typedef struct acc_s {
accDev_t dev; accDev_t dev;
uint32_t accTargetLooptime;
int32_t accADC[XYZ_AXIS_COUNT];
} acc_t; } acc_t;
extern sensor_align_e accAlign;
extern acc_t acc; extern acc_t acc;
extern int32_t accADC[XYZ_AXIS_COUNT]; typedef struct accelerometerConfig_s {
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 accTargetLooptime); void accInit(uint32_t accTargetLooptime);
bool isAccelerationCalibrationComplete(void); bool isAccelerationCalibrationComplete(void);

View file

@ -30,13 +30,14 @@ typedef enum {
} baroSensor_e; } baroSensor_e;
typedef struct barometerConfig_s { typedef struct barometerConfig_s {
uint8_t baro_hardware; // Barometer hardware to use
uint8_t use_median_filtering; // Use 3-point median filtering uint8_t use_median_filtering; // Use 3-point median filtering
} barometerConfig_t; } barometerConfig_t;
typedef struct baro_s { typedef struct baro_s {
baroDev_t dev; baroDev_t dev;
int32_t BaroAlt; int32_t BaroAlt;
int32_t baroTemperature; // Use temperature for telemetry int32_t baroTemperature; // Use temperature for telemetry
} baro_t; } baro_t;
extern baro_t baro; extern baro_t baro;

View file

@ -23,7 +23,7 @@
#include "common/maths.h" #include "common/maths.h"
#include "common/axis.h" #include "common/axis.h"
#include "sensors.h" #include "drivers/sensor.h"
#include "boardalignment.h" #include "boardalignment.h"

View file

@ -48,15 +48,15 @@ static int16_t magADCRaw[XYZ_AXIS_COUNT];
static uint8_t magInit = 0; static uint8_t magInit = 0;
static uint8_t magUpdatedAtLeastOnce = 0; static uint8_t magUpdatedAtLeastOnce = 0;
bool compassInit(int16_t magDeclinationFromConfig) bool compassInit(const compassConfig_t *compassConfig)
{ {
// initialize and calibration. turn on led during mag calibration (calibration routine blinks it) // initialize and calibration. turn on led during mag calibration (calibration routine blinks it)
LED1_ON; LED1_ON;
const bool ret = mag.dev.init(); const bool ret = mag.dev.init();
LED1_OFF; LED1_OFF;
if (ret) { if (ret) {
const int deg = magDeclinationFromConfig / 100; const int deg = compassConfig->mag_declination / 100;
const int min = magDeclinationFromConfig % 100; const int min = compassConfig->mag_declination % 100;
mag.magneticDeclination = (deg + ((float)min * (1.0f / 60.0f))) * 10; // heading is in 0.1deg units mag.magneticDeclination = (deg + ((float)min * (1.0f / 60.0f))) * 10; // heading is in 0.1deg units
magInit = 1; magInit = 1;
} }
@ -138,7 +138,7 @@ void compassUpdate(timeUs_t currentTimeUs, flightDynamicsTrims_t *magZero)
} }
} }
alignSensors(mag.magADC, mag.magAlign); alignSensors(mag.magADC, mag.dev.magAlign);
magUpdatedAtLeastOnce = 1; magUpdatedAtLeastOnce = 1;
} }

View file

@ -38,14 +38,20 @@ typedef enum {
typedef struct mag_s { typedef struct mag_s {
magDev_t dev; magDev_t dev;
sensor_align_e magAlign;
float magneticDeclination; float magneticDeclination;
int32_t magADC[XYZ_AXIS_COUNT]; int32_t magADC[XYZ_AXIS_COUNT];
} mag_t; } mag_t;
extern mag_t mag; extern mag_t mag;
bool compassInit(int16_t magDeclinationFromConfig); 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;
bool compassInit(const compassConfig_t *compassConfig);
union flightDynamicsTrims_u; union flightDynamicsTrims_u;
void compassUpdate(timeUs_t currentTimeUs, union flightDynamicsTrims_u *magZero); void compassUpdate(timeUs_t currentTimeUs, union flightDynamicsTrims_u *magZero);
bool isCompassReady(void); bool isCompassReady(void);

View file

@ -37,9 +37,6 @@
#include "config/config.h" #include "config/config.h"
gyro_t gyro; // gyro access functions gyro_t gyro; // gyro access functions
sensor_align_e gyroAlign = 0;
int32_t gyroADC[XYZ_AXIS_COUNT];
static int32_t gyroZero[XYZ_AXIS_COUNT] = { 0, 0, 0 }; static int32_t gyroZero[XYZ_AXIS_COUNT] = { 0, 0, 0 };
static const gyroConfig_t *gyroConfig; static const gyroConfig_t *gyroConfig;
@ -55,7 +52,7 @@ void gyroInit(const gyroConfig_t *gyroConfigToUse)
// no additional condition is required // no additional condition is required
// Set gyro sample rate before driver initialisation // Set gyro sample rate before driver initialisation
gyro.dev.lpf = gyroConfig->gyro_lpf; gyro.dev.lpf = gyroConfig->gyro_lpf;
gyro.dev.targetLooptime = gyroSetSampleRate(gyroConfig->looptime, gyroConfig->gyro_lpf, gyroConfig->gyroSync, gyroConfig->gyroSyncDenominator); gyro.targetLooptime = gyroSetSampleRate(gyroConfig->looptime, gyroConfig->gyro_lpf, gyroConfig->gyroSync, gyroConfig->gyroSyncDenominator);
// driver initialisation // driver initialisation
gyro.dev.init(&gyro.dev); gyro.dev.init(&gyro.dev);
if (gyroConfig->gyro_soft_lpf_hz) { if (gyroConfig->gyro_soft_lpf_hz) {
@ -63,7 +60,7 @@ void gyroInit(const gyroConfig_t *gyroConfigToUse)
#ifdef ASYNC_GYRO_PROCESSING #ifdef ASYNC_GYRO_PROCESSING
biquadFilterInitLPF(&gyroFilterLPF[axis], gyroConfig->gyro_soft_lpf_hz, getGyroUpdateRate()); biquadFilterInitLPF(&gyroFilterLPF[axis], gyroConfig->gyro_soft_lpf_hz, getGyroUpdateRate());
#else #else
biquadFilterInitLPF(&gyroFilterLPF[axis], gyroConfig->gyro_soft_lpf_hz, gyro.dev.targetLooptime); biquadFilterInitLPF(&gyroFilterLPF[axis], gyroConfig->gyro_soft_lpf_hz, gyro.targetLooptime);
#endif #endif
} }
} }
@ -103,11 +100,11 @@ static void performAcclerationCalibration(uint8_t gyroMovementCalibrationThresho
} }
// Sum up CALIBRATING_GYRO_CYCLES readings // Sum up CALIBRATING_GYRO_CYCLES readings
g[axis] += gyroADC[axis]; g[axis] += gyro.gyroADC[axis];
devPush(&var[axis], gyroADC[axis]); devPush(&var[axis], gyro.gyroADC[axis]);
// Reset global variables to prevent other code from using un-calibrated data // Reset global variables to prevent other code from using un-calibrated data
gyroADC[axis] = 0; gyro.gyroADC[axis] = 0;
gyroZero[axis] = 0; gyroZero[axis] = 0;
if (isOnFinalGyroCalibrationCycle()) { if (isOnFinalGyroCalibrationCycle()) {
@ -136,13 +133,13 @@ void gyroUpdate(void)
} }
// Prepare a copy of int32_t gyroADC for mangling to prevent overflow // Prepare a copy of int32_t gyroADC for mangling to prevent overflow
gyroADC[X] = gyro.dev.gyroADCRaw[X]; gyro.gyroADC[X] = gyro.dev.gyroADCRaw[X];
gyroADC[Y] = gyro.dev.gyroADCRaw[Y]; gyro.gyroADC[Y] = gyro.dev.gyroADCRaw[Y];
gyroADC[Z] = gyro.dev.gyroADCRaw[Z]; gyro.gyroADC[Z] = gyro.dev.gyroADCRaw[Z];
if (gyroConfig->gyro_soft_lpf_hz) { if (gyroConfig->gyro_soft_lpf_hz) {
for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) { for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) {
gyroADC[axis] = lrintf(biquadFilterApply(&gyroFilterLPF[axis], (float) gyroADC[axis])); gyro.gyroADC[axis] = lrintf(biquadFilterApply(&gyroFilterLPF[axis], (float)gyro.gyroADC[axis]));
} }
} }
@ -150,9 +147,9 @@ void gyroUpdate(void)
performAcclerationCalibration(gyroConfig->gyroMovementCalibrationThreshold); performAcclerationCalibration(gyroConfig->gyroMovementCalibrationThreshold);
} }
gyroADC[X] -= gyroZero[X]; gyro.gyroADC[X] -= gyroZero[X];
gyroADC[Y] -= gyroZero[Y]; gyro.gyroADC[Y] -= gyroZero[Y];
gyroADC[Z] -= gyroZero[Z]; gyro.gyroADC[Z] -= gyroZero[Z];
alignSensors(gyroADC, gyroAlign); alignSensors(gyro.gyroADC, gyro.dev.gyroAlign);
} }

View file

@ -18,6 +18,7 @@
#pragma once #pragma once
#include "drivers/accgyro.h" #include "drivers/accgyro.h"
#include "common/axis.h"
typedef enum { typedef enum {
GYRO_NONE = 0, GYRO_NONE = 0,
@ -34,13 +35,14 @@ typedef enum {
typedef struct gyro_s { typedef struct gyro_s {
gyroDev_t dev; gyroDev_t dev;
uint32_t targetLooptime;
int32_t gyroADC[XYZ_AXIS_COUNT];
} gyro_t; } gyro_t;
extern gyro_t gyro; extern gyro_t gyro;
extern int32_t gyroADC[XYZ_AXIS_COUNT];
typedef struct gyroConfig_s { typedef struct gyroConfig_s {
sensor_align_e gyro_align; // gyro alignment
uint8_t gyroMovementCalibrationThreshold; // people keep forgetting that moving model while init results in wrong gyro offsets. and then they never reset gyro. so this is now on by default. uint8_t gyroMovementCalibrationThreshold; // people keep forgetting that moving model while init results in wrong gyro offsets. and then they never reset gyro. so this is now on by default.
uint16_t looptime; // imu loop time in us uint16_t looptime; // imu loop time in us
uint8_t gyroSync; // Enable interrupt based loop uint8_t gyroSync; // Enable interrupt based loop

View file

@ -90,11 +90,6 @@
#include "hardware_revision.h" #include "hardware_revision.h"
#endif #endif
extern baro_t baro;
extern mag_t mag;
extern sensor_align_e gyroAlign;
extern pitot_t pitot;
uint8_t detectedSensors[SENSOR_INDEX_COUNT] = { GYRO_NONE, ACC_NONE, BARO_NONE, MAG_NONE, RANGEFINDER_NONE, PITOT_NONE }; uint8_t detectedSensors[SENSOR_INDEX_COUNT] = { GYRO_NONE, ACC_NONE, BARO_NONE, MAG_NONE, RANGEFINDER_NONE, PITOT_NONE };
@ -114,7 +109,7 @@ static bool detectGyro(gyroDev_t *dev)
{ {
gyroSensor_e gyroHardware = GYRO_DEFAULT; gyroSensor_e gyroHardware = GYRO_DEFAULT;
gyroAlign = ALIGN_DEFAULT; dev->gyroAlign = ALIGN_DEFAULT;
switch(gyroHardware) { switch(gyroHardware) {
case GYRO_DEFAULT: case GYRO_DEFAULT:
@ -124,7 +119,7 @@ static bool detectGyro(gyroDev_t *dev)
if (mpu6050GyroDetect(dev)) { if (mpu6050GyroDetect(dev)) {
gyroHardware = GYRO_MPU6050; gyroHardware = GYRO_MPU6050;
#ifdef GYRO_MPU6050_ALIGN #ifdef GYRO_MPU6050_ALIGN
gyroAlign = GYRO_MPU6050_ALIGN; dev->gyroAlign = GYRO_MPU6050_ALIGN;
#endif #endif
break; break;
} }
@ -135,7 +130,7 @@ static bool detectGyro(gyroDev_t *dev)
if (l3g4200dDetect(dev)) { if (l3g4200dDetect(dev)) {
gyroHardware = GYRO_L3G4200D; gyroHardware = GYRO_L3G4200D;
#ifdef GYRO_L3G4200D_ALIGN #ifdef GYRO_L3G4200D_ALIGN
gyroAlign = GYRO_L3G4200D_ALIGN; dev->gyroAlign = GYRO_L3G4200D_ALIGN;
#endif #endif
break; break;
} }
@ -147,7 +142,7 @@ static bool detectGyro(gyroDev_t *dev)
if (mpu3050Detect(dev)) { if (mpu3050Detect(dev)) {
gyroHardware = GYRO_MPU3050; gyroHardware = GYRO_MPU3050;
#ifdef GYRO_MPU3050_ALIGN #ifdef GYRO_MPU3050_ALIGN
gyroAlign = GYRO_MPU3050_ALIGN; dev->gyroAlign = GYRO_MPU3050_ALIGN;
#endif #endif
break; break;
} }
@ -159,7 +154,7 @@ static bool detectGyro(gyroDev_t *dev)
if (l3gd20Detect(dev)) { if (l3gd20Detect(dev)) {
gyroHardware = GYRO_L3GD20; gyroHardware = GYRO_L3GD20;
#ifdef GYRO_L3GD20_ALIGN #ifdef GYRO_L3GD20_ALIGN
gyroAlign = GYRO_L3GD20_ALIGN; dev->gyroAlign = GYRO_L3GD20_ALIGN;
#endif #endif
break; break;
} }
@ -171,7 +166,7 @@ static bool detectGyro(gyroDev_t *dev)
if (mpu6000SpiGyroDetect(dev)) { if (mpu6000SpiGyroDetect(dev)) {
gyroHardware = GYRO_MPU6000; gyroHardware = GYRO_MPU6000;
#ifdef GYRO_MPU6000_ALIGN #ifdef GYRO_MPU6000_ALIGN
gyroAlign = GYRO_MPU6000_ALIGN; dev->gyroAlign = GYRO_MPU6000_ALIGN;
#endif #endif
break; break;
} }
@ -187,7 +182,7 @@ static bool detectGyro(gyroDev_t *dev)
#endif #endif
gyroHardware = GYRO_MPU6500; gyroHardware = GYRO_MPU6500;
#ifdef GYRO_MPU6500_ALIGN #ifdef GYRO_MPU6500_ALIGN
gyroAlign = GYRO_MPU6500_ALIGN; dev->gyroAlign = GYRO_MPU6500_ALIGN;
#endif #endif
break; break;
@ -201,7 +196,7 @@ static bool detectGyro(gyroDev_t *dev)
{ {
gyroHardware = GYRO_MPU9250; gyroHardware = GYRO_MPU9250;
#ifdef GYRO_MPU9250_ALIGN #ifdef GYRO_MPU9250_ALIGN
gyroAlign = GYRO_MPU9250_ALIGN; dev->gyroAlign = GYRO_MPU9250_ALIGN;
#endif #endif
break; break;
@ -241,7 +236,7 @@ static bool detectAcc(accDev_t *dev, accelerationSensor_e accHardwareToUse)
#endif #endif
retry: retry:
accAlign = ALIGN_DEFAULT; dev->accAlign = ALIGN_DEFAULT;
switch (accHardwareToUse) { switch (accHardwareToUse) {
case ACC_DEFAULT: case ACC_DEFAULT:
@ -256,7 +251,7 @@ retry:
if (adxl345Detect(dev, &acc_params)) { if (adxl345Detect(dev, &acc_params)) {
#endif #endif
#ifdef ACC_ADXL345_ALIGN #ifdef ACC_ADXL345_ALIGN
accAlign = ACC_ADXL345_ALIGN; dev->accAlign = ACC_ADXL345_ALIGN;
#endif #endif
accHardware = ACC_ADXL345; accHardware = ACC_ADXL345;
break; break;
@ -267,7 +262,7 @@ retry:
#ifdef USE_ACC_LSM303DLHC #ifdef USE_ACC_LSM303DLHC
if (lsm303dlhcAccDetect(dev)) { if (lsm303dlhcAccDetect(dev)) {
#ifdef ACC_LSM303DLHC_ALIGN #ifdef ACC_LSM303DLHC_ALIGN
accAlign = ACC_LSM303DLHC_ALIGN; dev->accAlign = ACC_LSM303DLHC_ALIGN;
#endif #endif
accHardware = ACC_LSM303DLHC; accHardware = ACC_LSM303DLHC;
break; break;
@ -278,7 +273,7 @@ retry:
#ifdef USE_ACC_MPU6050 #ifdef USE_ACC_MPU6050
if (mpu6050AccDetect(dev)) { if (mpu6050AccDetect(dev)) {
#ifdef ACC_MPU6050_ALIGN #ifdef ACC_MPU6050_ALIGN
accAlign = ACC_MPU6050_ALIGN; dev->accAlign = ACC_MPU6050_ALIGN;
#endif #endif
accHardware = ACC_MPU6050; accHardware = ACC_MPU6050;
break; break;
@ -294,7 +289,7 @@ retry:
if (mma8452Detect(dev)) { if (mma8452Detect(dev)) {
#endif #endif
#ifdef ACC_MMA8452_ALIGN #ifdef ACC_MMA8452_ALIGN
accAlign = ACC_MMA8452_ALIGN; dev->accAlign = ACC_MMA8452_ALIGN;
#endif #endif
accHardware = ACC_MMA8452; accHardware = ACC_MMA8452;
break; break;
@ -305,7 +300,7 @@ retry:
#ifdef USE_ACC_BMA280 #ifdef USE_ACC_BMA280
if (bma280Detect(dev)) { if (bma280Detect(dev)) {
#ifdef ACC_BMA280_ALIGN #ifdef ACC_BMA280_ALIGN
accAlign = ACC_BMA280_ALIGN; dev->accAlign = ACC_BMA280_ALIGN;
#endif #endif
accHardware = ACC_BMA280; accHardware = ACC_BMA280;
break; break;
@ -316,7 +311,7 @@ retry:
#ifdef USE_ACC_SPI_MPU6000 #ifdef USE_ACC_SPI_MPU6000
if (mpu6000SpiAccDetect(dev)) { if (mpu6000SpiAccDetect(dev)) {
#ifdef ACC_MPU6000_ALIGN #ifdef ACC_MPU6000_ALIGN
accAlign = ACC_MPU6000_ALIGN; dev->accAlign = ACC_MPU6000_ALIGN;
#endif #endif
accHardware = ACC_MPU6000; accHardware = ACC_MPU6000;
break; break;
@ -331,7 +326,7 @@ retry:
if (mpu6500AccDetect(dev)) { if (mpu6500AccDetect(dev)) {
#endif #endif
#ifdef ACC_MPU6500_ALIGN #ifdef ACC_MPU6500_ALIGN
accAlign = ACC_MPU6500_ALIGN; dev->accAlign = ACC_MPU6500_ALIGN;
#endif #endif
accHardware = ACC_MPU6500; accHardware = ACC_MPU6500;
break; break;
@ -341,7 +336,7 @@ retry:
#ifdef USE_ACC_SPI_MPU9250 #ifdef USE_ACC_SPI_MPU9250
if (mpu9250SpiAccDetect(dev)) { if (mpu9250SpiAccDetect(dev)) {
#ifdef ACC_MPU9250_ALIGN #ifdef ACC_MPU9250_ALIGN
accAlign = ACC_MPU9250_ALIGN; dev->accAlign = ACC_MPU9250_ALIGN;
#endif #endif
accHardware = ACC_MPU9250; accHardware = ACC_MPU9250;
break; break;
@ -537,7 +532,7 @@ static bool detectMag(magDev_t *dev, magSensor_e magHardwareToUse)
#endif #endif
mag.magAlign = ALIGN_DEFAULT; dev->magAlign = ALIGN_DEFAULT;
switch(magHardwareToUse) { switch(magHardwareToUse) {
case MAG_DEFAULT: case MAG_DEFAULT:
@ -547,7 +542,7 @@ static bool detectMag(magDev_t *dev, magSensor_e magHardwareToUse)
#ifdef USE_MAG_HMC5883 #ifdef USE_MAG_HMC5883
if (hmc5883lDetect(dev, hmc5883Config)) { if (hmc5883lDetect(dev, hmc5883Config)) {
#ifdef MAG_HMC5883_ALIGN #ifdef MAG_HMC5883_ALIGN
mag.magAlign = MAG_HMC5883_ALIGN; dev->magAlign = MAG_HMC5883_ALIGN;
#endif #endif
magHardware = MAG_HMC5883; magHardware = MAG_HMC5883;
break; break;
@ -559,7 +554,7 @@ static bool detectMag(magDev_t *dev, magSensor_e magHardwareToUse)
#ifdef USE_MAG_AK8975 #ifdef USE_MAG_AK8975
if (ak8975Detect(dev)) { if (ak8975Detect(dev)) {
#ifdef MAG_AK8975_ALIGN #ifdef MAG_AK8975_ALIGN
mag.magAlign = MAG_AK8975_ALIGN; dev->magAlign = MAG_AK8975_ALIGN;
#endif #endif
magHardware = MAG_AK8975; magHardware = MAG_AK8975;
break; break;
@ -571,7 +566,7 @@ static bool detectMag(magDev_t *dev, magSensor_e magHardwareToUse)
#ifdef USE_MAG_AK8963 #ifdef USE_MAG_AK8963
if (ak8963Detect(dev)) { if (ak8963Detect(dev)) {
#ifdef MAG_AK8963_ALIGN #ifdef MAG_AK8963_ALIGN
mag.magAlign = MAG_AK8963_ALIGN; dev->magAlign = MAG_AK8963_ALIGN;
#endif #endif
magHardware = MAG_AK8963; magHardware = MAG_AK8963;
break; break;
@ -583,7 +578,7 @@ static bool detectMag(magDev_t *dev, magSensor_e magHardwareToUse)
#ifdef GPS #ifdef GPS
if (gpsMagDetect(dev)) { if (gpsMagDetect(dev)) {
#ifdef MAG_GPS_ALIGN #ifdef MAG_GPS_ALIGN
mag.magAlign = MAG_GPS_ALIGN; dev->magAlign = MAG_GPS_ALIGN;
#endif #endif
magHardware = MAG_GPS; magHardware = MAG_GPS;
break; break;
@ -595,7 +590,7 @@ static bool detectMag(magDev_t *dev, magSensor_e magHardwareToUse)
#ifdef USE_MAG_MAG3110 #ifdef USE_MAG_MAG3110
if (mag3110detect(dev)) { if (mag3110detect(dev)) {
#ifdef MAG_MAG3110_ALIGN #ifdef MAG_MAG3110_ALIGN
mag.magAlign = MAG_MAG3110_ALIGN; dev->magAlign = MAG_MAG3110_ALIGN;
#endif #endif
magHardware = MAG_MAG3110; magHardware = MAG_MAG3110;
break; break;
@ -661,23 +656,11 @@ static rangefinderType_e detectRangefinder(void)
} }
#endif #endif
static void reconfigureAlignment(const sensorAlignmentConfig_t *sensorAlignmentConfig) bool sensorsAutodetect(const gyroConfig_t *gyroConfig,
{ const accelerometerConfig_t *accConfig,
if (sensorAlignmentConfig->gyro_align != ALIGN_DEFAULT) { const compassConfig_t *compassConfig,
gyroAlign = sensorAlignmentConfig->gyro_align; const barometerConfig_t *baroConfig,
} const pitotmeterConfig_t *pitotConfig)
if (sensorAlignmentConfig->acc_align != ALIGN_DEFAULT) {
accAlign = sensorAlignmentConfig->acc_align;
}
if (sensorAlignmentConfig->mag_align != ALIGN_DEFAULT) {
mag.magAlign = sensorAlignmentConfig->mag_align;
}
}
bool sensorsAutodetect(const sensorAlignmentConfig_t *sensorAlignmentConfig,
const sensorSelectionConfig_t *sensorSelectionConfig,
int16_t magDeclinationFromConfig,
const gyroConfig_t *gyroConfig)
{ {
#if defined(USE_GYRO_MPU6050) || defined(USE_GYRO_MPU3050) || defined(USE_GYRO_MPU6500) || defined(USE_GYRO_SPI_MPU6500) || defined(USE_GYRO_SPI_MPU6000) || defined(USE_ACC_MPU6050) || defined(USE_GYRO_SPI_MPU9250) #if defined(USE_GYRO_MPU6050) || defined(USE_GYRO_MPU3050) || defined(USE_GYRO_MPU6500) || defined(USE_GYRO_SPI_MPU6500) || defined(USE_GYRO_SPI_MPU6000) || defined(USE_ACC_MPU6050) || defined(USE_GYRO_SPI_MPU9250)
const extiConfig_t *extiConfig = selectMPUIntExtiConfig(); const extiConfig_t *extiConfig = selectMPUIntExtiConfig();
@ -691,43 +674,53 @@ bool sensorsAutodetect(const sensorAlignmentConfig_t *sensorAlignmentConfig,
gyroInit(gyroConfig); gyroInit(gyroConfig);
memset(&acc, 0, sizeof(acc)); memset(&acc, 0, sizeof(acc));
if (detectAcc(&acc.dev, sensorSelectionConfig->acc_hardware)) { if (detectAcc(&acc.dev, accConfig->acc_hardware)) {
#ifdef ASYNC_GYRO_PROCESSING #ifdef ASYNC_GYRO_PROCESSING
// ACC will be updated at its own rate // ACC will be updated at its own rate
accInit(getAccUpdateRate()); accInit(getAccUpdateRate());
#else #else
// acc updated at same frequency in taskMainPidLoop in mw.c // acc updated at same frequency in taskMainPidLoop in mw.c
accInit(gyro.dev.targetLooptime); accInit(gyro.targetLooptime);
#endif #endif
} }
#ifdef BARO #ifdef BARO
detectBaro(&baro.dev, sensorSelectionConfig->baro_hardware); detectBaro(&baro.dev, baroConfig->baro_hardware);
#endif #endif
#ifdef PITOT #ifdef PITOT
detectPitot(sensorSelectionConfig->pitot_hardware); detectPitot(pitotConfig->pitot_hardware);
#else
UNUSED(pitotConfig);
#endif #endif
// FIXME extract to a method to reduce dependencies, maybe move to sensors_compass.c // FIXME extract to a method to reduce dependencies, maybe move to sensors_compass.c
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. 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 #ifdef MAG
if (detectMag(&mag.dev, sensorSelectionConfig->mag_hardware)) { if (detectMag(&mag.dev, compassConfig->mag_hardware)) {
// calculate magnetic declination // calculate magnetic declination
if (!compassInit(magDeclinationFromConfig)) { if (!compassInit(compassConfig)) {
addBootlogEvent2(BOOT_EVENT_MAG_INIT_FAILED, BOOT_EVENT_FLAGS_ERROR); addBootlogEvent2(BOOT_EVENT_MAG_INIT_FAILED, BOOT_EVENT_FLAGS_ERROR);
sensorsClear(SENSOR_MAG); sensorsClear(SENSOR_MAG);
} }
} }
#else #else
UNUSED(magDeclinationFromConfig); UNUSED(compassConfig);
#endif #endif
#ifdef SONAR #ifdef SONAR
const rangefinderType_e rangefinderType = detectRangefinder(); const rangefinderType_e rangefinderType = detectRangefinder();
rangefinderInit(rangefinderType); rangefinderInit(rangefinderType);
#endif #endif
reconfigureAlignment(sensorAlignmentConfig); 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 (compassConfig->mag_align != ALIGN_DEFAULT) {
mag.dev.magAlign = compassConfig->mag_align;
}
return true; return true;
} }

View file

@ -17,10 +17,8 @@
#pragma once #pragma once
struct sensorAlignmentConfig_s; bool sensorsAutodetect(const gyroConfig_t *gyroConfig,
struct sensorSelectionConfig_s; const accelerometerConfig_t *accConfig,
struct gyroConfig_s; const compassConfig_t *compassConfig,
bool sensorsAutodetect(const struct sensorAlignmentConfig_s *sensorAlignmentConfig, const barometerConfig_t *baroConfig,
const struct sensorSelectionConfig_s *sensorSelectionConfig, const pitotmeterConfig_t *pitotConfig);
int16_t magDeclinationFromConfig,
const struct gyroConfig_s *gyroConfig);

View file

@ -28,9 +28,10 @@ typedef enum {
#define PITOT_SAMPLE_COUNT_MAX 48 #define PITOT_SAMPLE_COUNT_MAX 48
typedef struct pitotmeterConfig_s { typedef struct pitotmeterConfig_s {
uint8_t use_median_filtering; // Use 3-point median filtering uint8_t use_median_filtering; // Use 3-point median filtering
float pitot_noise_lpf; // additional LPF to reduce pitot noise uint8_t pitot_hardware; // Pitotmeter hardware to use
float pitot_scale; // scale value float pitot_noise_lpf; // additional LPF to reduce pitot noise
float pitot_scale; // scale value
} pitotmeterConfig_t; } pitotmeterConfig_t;
extern int32_t AirSpeed; extern int32_t AirSpeed;

View file

@ -55,31 +55,6 @@ typedef enum {
SENSOR_GPSMAG = 1 << 7, SENSOR_GPSMAG = 1 << 7,
} sensors_e; } sensors_e;
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 struct sensorAlignmentConfig_s {
sensor_align_e gyro_align; // gyro alignment
sensor_align_e acc_align; // acc alignment
sensor_align_e mag_align; // mag alignment
} sensorAlignmentConfig_t;
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
uint8_t pitot_hardware; // Pitotmeter hardware to use
} sensorSelectionConfig_t;
typedef struct sensorTrims_s { typedef struct sensorTrims_s {
flightDynamicsTrims_t accZero; // Accelerometer offset flightDynamicsTrims_t accZero; // Accelerometer offset
flightDynamicsTrims_t accGain; // Accelerometer gain to read exactly 1G flightDynamicsTrims_t accGain; // Accelerometer gain to read exactly 1G

View file

@ -164,7 +164,7 @@ static void sendAccel(void)
for (i = 0; i < 3; i++) { for (i = 0; i < 3; i++) {
sendDataHead(ID_ACC_X + i); sendDataHead(ID_ACC_X + i);
serialize16(accADC[i] * 1000 / acc.dev.acc_1G); serialize16(acc.accADC[i] * 1000 / acc.dev.acc_1G);
} }
} }

View file

@ -380,15 +380,15 @@ void handleSmartPortTelemetry(void)
smartPortHasRequest = 0; smartPortHasRequest = 0;
break; break;
case FSSP_DATAID_ACCX : case FSSP_DATAID_ACCX :
smartPortSendPackage(id, 100 * accADC[X] / acc.dev.acc_1G); smartPortSendPackage(id, 100 * acc.accADC[X] / acc.dev.acc_1G);
smartPortHasRequest = 0; smartPortHasRequest = 0;
break; break;
case FSSP_DATAID_ACCY : case FSSP_DATAID_ACCY :
smartPortSendPackage(id, 100 * accADC[Y] / acc.dev.acc_1G); smartPortSendPackage(id, 100 * acc.accADC[Y] / acc.dev.acc_1G);
smartPortHasRequest = 0; smartPortHasRequest = 0;
break; break;
case FSSP_DATAID_ACCZ : case FSSP_DATAID_ACCZ :
smartPortSendPackage(id, 100 * accADC[Z] / acc.dev.acc_1G); smartPortSendPackage(id, 100 * acc.accADC[Z] / acc.dev.acc_1G);
smartPortHasRequest = 0; smartPortHasRequest = 0;
break; break;
case FSSP_DATAID_T1 : case FSSP_DATAID_T1 :