1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-19 14:25:20 +03:00

Cleanup baro/mag/gyro/acc method names from old sensors.c

This commit is contained in:
Dominic Clifton 2014-04-22 02:43:39 +01:00
parent 7e76fd6995
commit 9f26018abd
12 changed files with 38 additions and 43 deletions

View file

@ -83,7 +83,7 @@ void imuInit(void)
#ifdef MAG
// if mag sensor is enabled, use it
if (sensors(SENSOR_MAG))
Mag_init();
compassInit();
#endif
}
@ -92,9 +92,9 @@ void computeIMU(void)
uint32_t axis;
static int16_t gyroYawSmooth = 0;
Gyro_getADC();
gyroGetADC();
if (sensors(SENSOR_ACC)) {
ACC_getADC();
accGetADC();
getEstimatedAttitude();
} else {
accADC[X] = 0;
@ -406,7 +406,7 @@ int getEstimatedAltitude(void)
vel = 0;
accAlt = 0;
}
BaroAlt = Baro_calculateAltitude();
BaroAlt = baroCalculateAltitude();
dt = accTimeSum * 1e-6f; // delta acc reading time in seconds

View file

@ -193,11 +193,11 @@ int main(void)
previousTime = micros();
if (masterConfig.mixerConfiguration == MULTITYPE_GIMBAL) {
ACC_SetCalibrationCycles(CALIBRATING_ACC_CYCLES);
accSetCalibrationCycles(CALIBRATING_ACC_CYCLES);
}
GYRO_SetCalibrationCycles(CALIBRATING_GYRO_CYCLES);
gyroSetCalibrationCycles(CALIBRATING_GYRO_CYCLES);
#ifdef BARO
Baro_SetCalibrationCycles(CALIBRATING_BARO_CYCLES);
baroSetCalibrationCycles(CALIBRATING_BARO_CYCLES);
#endif
f.SMALL_ANGLE = 1;

View file

@ -6,6 +6,8 @@
#include "sensors_sonar.h"
#include "sensors_gyro.h"
#include "sensors_compass.h"
#include "sensors_barometer.h"
#include "flight_common.h"
#include "serial_cli.h"
#include "telemetry_common.h"
@ -479,13 +481,13 @@ void loop(void)
case 0:
taskOrder++;
#ifdef MAG
if (sensors(SENSOR_MAG) && Mag_getADC())
if (sensors(SENSOR_MAG) && compassGetADC())
break;
#endif
case 1:
taskOrder++;
#ifdef BARO
if (sensors(SENSOR_BARO) && Baro_update())
if (sensors(SENSOR_BARO) && baroUpdate())
break;
#endif
case 2:

View file

@ -64,13 +64,6 @@ void annexCode(void);
void computeIMU(void);
int getEstimatedAltitude(void);
// Sensors
void ACC_getADC(void);
int Baro_update(void);
void Gyro_getADC(void);
void Mag_init(void);
int Mag_getADC(void);
// Output
void mixerResetMotors(void);
void mixerLoadMix(int index);

View file

@ -18,12 +18,12 @@ extern bool AccInflightCalibrationMeasurementDone;
extern bool AccInflightCalibrationSavetoEEProm;
extern bool AccInflightCalibrationActive;
void ACC_SetCalibrationCycles(uint16_t calibrationCyclesRequired)
void accSetCalibrationCycles(uint16_t calibrationCyclesRequired)
{
calibratingA = calibrationCyclesRequired;
}
void ACC_Common(void)
void accCommon(void)
{
static int32_t a[3];
int axis;
@ -109,11 +109,11 @@ void ACC_Common(void)
accADC[GI_YAW] -= masterConfig.accZero[GI_YAW];
}
void ACC_getADC(void)
void accGetADC(void)
{
acc.read(accADC);
alignSensors(accADC, accADC, accAlign);
ACC_Common();
accCommon();
}

View file

@ -15,7 +15,7 @@ extern sensor_align_e accAlign;
extern acc_t acc;
extern uint16_t calibratingA;
void ACC_SetCalibrationCycles(uint16_t calibrationCyclesRequired);
void ACC_Common(void);
void ACC_getADC(void);
void accSetCalibrationCycles(uint16_t calibrationCyclesRequired);
void accCommon(void);
void accGetADC(void);

View file

@ -11,12 +11,12 @@ uint16_t calibratingB = 0; // baro calibration = get new ground pressure va
static int32_t baroGroundAltitude = 0;
static int32_t baroGroundPressure = 0;
void Baro_SetCalibrationCycles(uint16_t calibrationCyclesRequired)
void baroSetCalibrationCycles(uint16_t calibrationCyclesRequired)
{
calibratingB = calibrationCyclesRequired;
}
void Baro_Common(void)
void baroCommon(void)
{
static int32_t baroHistTab[BARO_TAB_SIZE_MAX];
static int baroHistIdx;
@ -32,7 +32,7 @@ void Baro_Common(void)
}
int Baro_update(void)
int baroUpdate(void)
{
static uint32_t baroDeadline = 0;
static int state = 0;
@ -52,14 +52,14 @@ int Baro_update(void)
} else {
baro.get_ut();
baro.start_up();
Baro_Common();
baroCommon();
state = 1;
baroDeadline += baro.up_delay;
return 1;
}
}
int32_t Baro_calculateAltitude(void)
int32_t baroCalculateAltitude(void)
{
int32_t BaroAlt_tmp;

View file

@ -1,10 +1,10 @@
#pragma once
#ifdef BARO
void Baro_SetCalibrationCycles(uint16_t calibrationCyclesRequired);
void Baro_Common(void);
int Baro_update(void);
int32_t Baro_calculateAltitude(void);
void baroSetCalibrationCycles(uint16_t calibrationCyclesRequired);
void baroCommon(void);
int baroUpdate(void);
int32_t baroCalculateAltitude(void);
bool isBaroCalibrationComplete(void);
void performBaroCalibrationCycle(void);
#endif

View file

@ -8,7 +8,7 @@ sensor_align_e magAlign = 0;
#ifdef MAG
static uint8_t magInit = 0;
void Mag_init(void)
void compassInit(void)
{
// initialize and calibration. turn on led during mag calibration (calibration routine blinks it)
LED1_ON;
@ -17,7 +17,7 @@ void Mag_init(void)
magInit = 1;
}
int Mag_getADC(void)
int compassGetADC(void)
{
static uint32_t t, tCal = 0;
static int16_t magZeroTempMin[3];

View file

@ -1,8 +1,8 @@
#pragma once
#ifdef MAG
void Mag_init(void);
int Mag_getADC(void);
void compassInit(void);
int compassGetADC(void);
#endif
extern int16_t magADC[XYZ_AXIS_COUNT];

View file

@ -11,12 +11,12 @@ uint16_t acc_1G = 256; // this is the 1G measured acceleration.
gyro_t gyro; // gyro access functions
sensor_align_e gyroAlign = 0;
void GYRO_SetCalibrationCycles(uint16_t calibrationCyclesRequired)
void gyroSetCalibrationCycles(uint16_t calibrationCyclesRequired)
{
calibratingG = calibrationCyclesRequired;
}
void GYRO_Common(void)
void gyroCommon(void)
{
int axis;
static int32_t g[3];
@ -56,10 +56,10 @@ void GYRO_Common(void)
gyroADC[axis] -= gyroZero[axis];
}
void Gyro_getADC(void)
void gyroGetADC(void)
{
// range: +/- 8192; +/- 2000 deg/sec
gyro.read(gyroADC);
alignSensors(gyroADC, gyroADC, gyroAlign);
GYRO_Common();
gyroCommon();
}

View file

@ -4,7 +4,7 @@ extern uint16_t acc_1G;
extern gyro_t gyro;
extern sensor_align_e gyroAlign;
void GYRO_SetCalibrationCycles(uint16_t calibrationCyclesRequired);
void GYRO_Common(void);
void Gyro_getADC(void);
void gyroSetCalibrationCycles(uint16_t calibrationCyclesRequired);
void gyroCommon(void);
void gyroGetADC(void);