1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-24 00:35:39 +03:00

Introduce better naming consistency for some union members. remove type

prefix from a typedef.

Conflicts:

	obj/cleanflight_OLIMEXINO.hex
	src/flight_common.c
This commit is contained in:
Dominic Clifton 2014-05-28 20:04:07 +01:00
parent dcbb82c845
commit 4a23491d49
16 changed files with 68 additions and 68 deletions

View file

@ -28,7 +28,7 @@ extern bool AccInflightCalibrationMeasurementDone;
extern bool AccInflightCalibrationSavetoEEProm;
extern bool AccInflightCalibrationActive;
static int16_flightDynamicsTrims_t *accelerationTrims;
static flightDynamicsTrims_t *accelerationTrims;
void accSetCalibrationCycles(uint16_t calibrationCyclesRequired)
{
@ -95,8 +95,8 @@ void performInflightAccelerationCalibration(rollAndPitchTrims_t *rollAndPitchTri
accZero_saved[FD_ROLL] = accelerationTrims->raw[FD_ROLL];
accZero_saved[FD_PITCH] = accelerationTrims->raw[FD_PITCH];
accZero_saved[FD_YAW] = accelerationTrims->raw[FD_YAW];
angleTrim_saved.trims.roll = rollAndPitchTrims->trims.roll;
angleTrim_saved.trims.pitch = rollAndPitchTrims->trims.pitch;
angleTrim_saved.values.roll = rollAndPitchTrims->values.roll;
angleTrim_saved.values.pitch = rollAndPitchTrims->values.pitch;
}
if (InflightcalibratingA > 0) {
for (axis = 0; axis < 3; axis++) {
@ -118,8 +118,8 @@ void performInflightAccelerationCalibration(rollAndPitchTrims_t *rollAndPitchTri
accelerationTrims->raw[FD_ROLL] = accZero_saved[FD_ROLL];
accelerationTrims->raw[FD_PITCH] = accZero_saved[FD_PITCH];
accelerationTrims->raw[FD_YAW] = accZero_saved[FD_YAW];
rollAndPitchTrims->trims.roll = angleTrim_saved.trims.roll;
rollAndPitchTrims->trims.pitch = angleTrim_saved.trims.pitch;
rollAndPitchTrims->values.roll = angleTrim_saved.values.roll;
rollAndPitchTrims->values.pitch = angleTrim_saved.values.pitch;
}
InflightcalibratingA--;
}
@ -137,7 +137,7 @@ void performInflightAccelerationCalibration(rollAndPitchTrims_t *rollAndPitchTri
}
void applyAccelerationTrims(int16_flightDynamicsTrims_t *accelerationTrims)
void applyAccelerationTrims(flightDynamicsTrims_t *accelerationTrims)
{
accADC[FD_ROLL] -= accelerationTrims->raw[FD_ROLL];
accADC[FD_PITCH] -= accelerationTrims->raw[FD_PITCH];
@ -160,7 +160,7 @@ void updateAccelerationReadings(rollAndPitchTrims_t *rollAndPitchTrims)
applyAccelerationTrims(accelerationTrims);
}
void setAccelerationTrims(int16_flightDynamicsTrims_t *accelerationTrimsToUse)
void setAccelerationTrims(flightDynamicsTrims_t *accelerationTrimsToUse)
{
accelerationTrims = accelerationTrimsToUse;
}