1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-13 19:40:31 +03:00

Removed leftover references to 'gyro_align', 'acc_align'.

This commit is contained in:
mikeller 2019-02-01 01:50:40 +13:00
parent ae194f2eb3
commit 21edada68b
6 changed files with 8 additions and 13 deletions

View file

@ -1280,8 +1280,8 @@ static bool mspProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst)
break;
case MSP_SENSOR_ALIGNMENT:
sbufWriteU8(dst, gyroConfig()->gyro_align);
sbufWriteU8(dst, accelerometerConfig()->acc_align);
sbufWriteU8(dst, 0); // gyro_align
sbufWriteU8(dst, 0); // acc_align
sbufWriteU8(dst, compassConfig()->mag_align);
break;
@ -1838,8 +1838,8 @@ static mspResult_e mspProcessInCommand(uint8_t cmdMSP, sbuf_t *src)
resetPidProfile(currentPidProfile);
break;
case MSP_SET_SENSOR_ALIGNMENT:
gyroConfigMutable()->gyro_align = sbufReadU8(src);
accelerometerConfigMutable()->acc_align = sbufReadU8(src);
sbufReadU8(src); // gyro_align
sbufReadU8(src); // acc_align
compassConfigMutable()->mag_align = sbufReadU8(src);
break;

View file

@ -100,7 +100,7 @@ static flightDynamicsTrims_t *accelerationTrims;
static uint16_t accLpfCutHz = 0;
static biquadFilter_t accFilter[XYZ_AXIS_COUNT];
PG_REGISTER_WITH_RESET_FN(accelerometerConfig_t, accelerometerConfig, PG_ACCELEROMETER_CONFIG, 0);
PG_REGISTER_WITH_RESET_FN(accelerometerConfig_t, accelerometerConfig, PG_ACCELEROMETER_CONFIG, 1);
void resetRollAndPitchTrims(rollAndPitchTrims_t *rollAndPitchTrims)
{
@ -131,7 +131,6 @@ void pgResetFn_accelerometerConfig(accelerometerConfig_t *instance)
{
RESET_CONFIG_2(accelerometerConfig_t, instance,
.acc_lpf_hz = 10,
.acc_align = ALIGN_DEFAULT,
.acc_hardware = ACC_DEFAULT,
.acc_high_fsr = false,
);

View file

@ -68,7 +68,6 @@ 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
bool acc_high_fsr;
flightDynamicsTrims_t accZero;

View file

@ -189,7 +189,7 @@ static void gyroInitLowpassFilterLpf(gyroSensor_t *gyroSensor, int slot, int typ
#define GYRO_OVERFLOW_TRIGGER_THRESHOLD 31980 // 97.5% full scale (1950dps for 2000dps gyro)
#define GYRO_OVERFLOW_RESET_THRESHOLD 30340 // 92.5% full scale (1850dps for 2000dps gyro)
PG_REGISTER_WITH_RESET_FN(gyroConfig_t, gyroConfig, PG_GYRO_CONFIG, 6);
PG_REGISTER_WITH_RESET_FN(gyroConfig_t, gyroConfig, PG_GYRO_CONFIG, 7);
#ifndef GYRO_CONFIG_USE_GYRO_DEFAULT
#define GYRO_CONFIG_USE_GYRO_DEFAULT GYRO_CONFIG_USE_GYRO_1
@ -197,7 +197,6 @@ PG_REGISTER_WITH_RESET_FN(gyroConfig_t, gyroConfig, PG_GYRO_CONFIG, 6);
void pgResetFn_gyroConfig(gyroConfig_t *gyroConfig)
{
gyroConfig->gyro_align = ALIGN_DEFAULT;
gyroConfig->gyroCalibrationDuration = 125; // 1.25 seconds
gyroConfig->gyroMovementCalibrationThreshold = 48;
gyroConfig->gyro_sync_denom = GYRO_SYNC_DENOM_DEFAULT;

View file

@ -69,7 +69,6 @@ typedef enum {
} filterSlots;
typedef struct gyroConfig_s {
uint8_t 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 gyro_sync_denom; // Gyro sample divider
uint8_t gyro_hardware_lpf; // gyro DLPF setting

View file

@ -32,11 +32,11 @@
#include "drivers/adc.h"
#include "drivers/io.h"
#include "sensors/acceleration.h"
#include "sensors/gyro.h"
#include "pg/adc.h"
#include "pg/beeper_dev.h"
#include "pg/gyrodev.h"
#include "hardware_revision.h"
@ -47,8 +47,7 @@
void targetConfiguration(void)
{
if (hardwareRevision == BJF4_REV1 || hardwareRevision == BJF4_REV2) {
gyroConfigMutable()->gyro_align = CW180_DEG;
accelerometerConfigMutable()->acc_align = CW180_DEG;
gyroDeviceConfigMutable(0)->align = CW180_DEG;
beeperDevConfigMutable()->ioTag = IO_TAG(BEEPER_OPT);
}