mirror of
https://github.com/iNavFlight/inav.git
synced 2025-07-24 00:35:34 +03:00
Rationalisation of sensor function names
This commit is contained in:
parent
2725e6a9fc
commit
78350e829b
18 changed files with 67 additions and 66 deletions
|
@ -420,8 +420,8 @@ static void activateConfig(void)
|
||||||
|
|
||||||
failsafeReset();
|
failsafeReset();
|
||||||
|
|
||||||
setAccelerationCalibrationValues();
|
accSetCalibrationValues();
|
||||||
setAccelerationFilter();
|
accInitFilters();
|
||||||
|
|
||||||
imuConfigure();
|
imuConfigure();
|
||||||
|
|
||||||
|
|
|
@ -565,7 +565,7 @@ static bool mspFcProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst, mspPostProcessFn
|
||||||
sbufWriteU8(dst, getConfigProfile());
|
sbufWriteU8(dst, getConfigProfile());
|
||||||
sbufWriteU16(dst, averageSystemLoadPercent);
|
sbufWriteU16(dst, averageSystemLoadPercent);
|
||||||
sbufWriteU16(dst, armingFlags);
|
sbufWriteU16(dst, armingFlags);
|
||||||
sbufWriteU8(dst, getAccelerometerCalibrationAxisFlags());
|
sbufWriteU8(dst, accGetCalibrationAxisFlags());
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case MSP_STATUS:
|
case MSP_STATUS:
|
||||||
|
|
|
@ -103,7 +103,7 @@ void taskUpdateBattery(timeUs_t currentTimeUs)
|
||||||
if (cmpTimeUs(currentTimeUs, vbatLastServiced) >= VBATINTERVAL) {
|
if (cmpTimeUs(currentTimeUs, vbatLastServiced) >= VBATINTERVAL) {
|
||||||
timeUs_t vbatTimeDelta = currentTimeUs - vbatLastServiced;
|
timeUs_t vbatTimeDelta = currentTimeUs - vbatLastServiced;
|
||||||
vbatLastServiced = currentTimeUs;
|
vbatLastServiced = currentTimeUs;
|
||||||
updateBattery(vbatTimeDelta);
|
batteryUpdate(vbatTimeDelta);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -112,7 +112,7 @@ void taskUpdateBattery(timeUs_t currentTimeUs)
|
||||||
|
|
||||||
if (ibatTimeSinceLastServiced >= IBATINTERVAL) {
|
if (ibatTimeSinceLastServiced >= IBATINTERVAL) {
|
||||||
ibatLastServiced = currentTimeUs;
|
ibatLastServiced = currentTimeUs;
|
||||||
updateCurrentMeter(ibatTimeSinceLastServiced, flight3DConfig()->deadband3d_throttle);
|
currentMeterUpdate(ibatTimeSinceLastServiced, flight3DConfig()->deadband3d_throttle);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
|
@ -105,14 +105,14 @@ static bool isRXDataNew;
|
||||||
bool isCalibrating(void)
|
bool isCalibrating(void)
|
||||||
{
|
{
|
||||||
#ifdef BARO
|
#ifdef BARO
|
||||||
if (sensors(SENSOR_BARO) && !isBaroCalibrationComplete()) {
|
if (sensors(SENSOR_BARO) && !baroIsCalibrationComplete()) {
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Note: compass calibration is handled completely differently, outside of the main loop, see f.CALIBRATE_MAG
|
// Note: compass calibration is handled completely differently, outside of the main loop, see f.CALIBRATE_MAG
|
||||||
|
|
||||||
return (!isAccelerationCalibrationComplete() && sensors(SENSOR_ACC)) || (!gyroIsCalibrationComplete());
|
return (!accIsCalibrationComplete() && sensors(SENSOR_ACC)) || (!gyroIsCalibrationComplete());
|
||||||
}
|
}
|
||||||
|
|
||||||
int16_t getAxisRcCommand(int16_t rawData, int16_t rate, int16_t deadband)
|
int16_t getAxisRcCommand(int16_t rawData, int16_t rate, int16_t deadband)
|
||||||
|
|
|
@ -3275,6 +3275,13 @@ static void cliSet(char *cmdline)
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
static const char * getBatteryStateString(void)
|
||||||
|
{
|
||||||
|
static const char * const batteryStateStrings[] = {"OK", "WARNING", "CRITICAL", "NOT PRESENT"};
|
||||||
|
|
||||||
|
return batteryStateStrings[getBatteryState()];
|
||||||
|
}
|
||||||
|
|
||||||
static void cliStatus(char *cmdline)
|
static void cliStatus(char *cmdline)
|
||||||
{
|
{
|
||||||
UNUSED(cmdline);
|
UNUSED(cmdline);
|
||||||
|
|
|
@ -610,12 +610,12 @@ void imuUpdateAccelerometer(void)
|
||||||
{
|
{
|
||||||
#ifdef HIL
|
#ifdef HIL
|
||||||
if (sensors(SENSOR_ACC) && !hilActive) {
|
if (sensors(SENSOR_ACC) && !hilActive) {
|
||||||
updateAccelerationReadings();
|
accUpdate();
|
||||||
isAccelUpdatedAtLeastOnce = true;
|
isAccelUpdatedAtLeastOnce = true;
|
||||||
}
|
}
|
||||||
#else
|
#else
|
||||||
if (sensors(SENSOR_ACC)) {
|
if (sensors(SENSOR_ACC)) {
|
||||||
updateAccelerationReadings();
|
accUpdate();
|
||||||
isAccelUpdatedAtLeastOnce = true;
|
isAccelUpdatedAtLeastOnce = true;
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -419,7 +419,7 @@ static void updateBaroTopic(timeUs_t currentTimeUs)
|
||||||
initialBaroAltitudeOffset = newBaroAlt;
|
initialBaroAltitudeOffset = newBaroAlt;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (sensors(SENSOR_BARO) && isBaroCalibrationComplete()) {
|
if (sensors(SENSOR_BARO) && baroIsCalibrationComplete()) {
|
||||||
posEstimator.baro.alt = newBaroAlt - initialBaroAltitudeOffset;
|
posEstimator.baro.alt = newBaroAlt - initialBaroAltitudeOffset;
|
||||||
posEstimator.baro.epv = positionEstimationConfig()->baro_epv;
|
posEstimator.baro.epv = positionEstimationConfig()->baro_epv;
|
||||||
posEstimator.baro.lastUpdateTime = currentTimeUs;
|
posEstimator.baro.lastUpdateTime = currentTimeUs;
|
||||||
|
@ -443,7 +443,7 @@ static void updatePitotTopic(timeUs_t currentTimeUs)
|
||||||
|
|
||||||
if (updateTimer(&pitotUpdateTimer, HZ2US(INAV_PITOT_UPDATE_RATE), currentTimeUs)) {
|
if (updateTimer(&pitotUpdateTimer, HZ2US(INAV_PITOT_UPDATE_RATE), currentTimeUs)) {
|
||||||
float newTAS = pitotCalculateAirSpeed();
|
float newTAS = pitotCalculateAirSpeed();
|
||||||
if (sensors(SENSOR_PITOT) && isPitotCalibrationComplete()) {
|
if (sensors(SENSOR_PITOT) && pitotIsCalibrationComplete()) {
|
||||||
posEstimator.pitot.airspeed = newTAS;
|
posEstimator.pitot.airspeed = newTAS;
|
||||||
}
|
}
|
||||||
else {
|
else {
|
||||||
|
|
|
@ -17,6 +17,8 @@
|
||||||
|
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
|
#include "config/parameter_group.h"
|
||||||
|
|
||||||
#if defined(USE_QUAD_MIXER_ONLY)
|
#if defined(USE_QUAD_MIXER_ONLY)
|
||||||
#define MAX_SUPPORTED_SERVOS 1
|
#define MAX_SUPPORTED_SERVOS 1
|
||||||
#else
|
#else
|
||||||
|
|
|
@ -264,7 +264,7 @@ bool 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);
|
||||||
acc.accTargetLooptime = targetLooptime;
|
acc.accTargetLooptime = targetLooptime;
|
||||||
setAccelerationFilter();
|
accInitFilters();
|
||||||
if (accelerometerConfig()->acc_align != ALIGN_DEFAULT) {
|
if (accelerometerConfig()->acc_align != ALIGN_DEFAULT) {
|
||||||
acc.dev.accAlign = accelerometerConfig()->acc_align;
|
acc.dev.accAlign = accelerometerConfig()->acc_align;
|
||||||
}
|
}
|
||||||
|
@ -276,17 +276,17 @@ void accSetCalibrationCycles(uint16_t calibrationCyclesRequired)
|
||||||
calibratingA = calibrationCyclesRequired;
|
calibratingA = calibrationCyclesRequired;
|
||||||
}
|
}
|
||||||
|
|
||||||
bool isAccelerationCalibrationComplete(void)
|
bool accIsCalibrationComplete(void)
|
||||||
{
|
{
|
||||||
return calibratingA == 0;
|
return calibratingA == 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
bool isOnFinalAccelerationCalibrationCycle(void)
|
static bool isOnFinalAccelerationCalibrationCycle(void)
|
||||||
{
|
{
|
||||||
return calibratingA == 1;
|
return calibratingA == 1;
|
||||||
}
|
}
|
||||||
|
|
||||||
bool isOnFirstAccelerationCalibrationCycle(void)
|
static bool isOnFirstAccelerationCalibrationCycle(void)
|
||||||
{
|
{
|
||||||
return calibratingA == CALIBRATING_ACC_CYCLES;
|
return calibratingA == CALIBRATING_ACC_CYCLES;
|
||||||
}
|
}
|
||||||
|
@ -296,9 +296,9 @@ static bool calibratedAxis[6];
|
||||||
static int32_t accSamples[6][3];
|
static int32_t accSamples[6][3];
|
||||||
static int calibratedAxisCount = 0;
|
static int calibratedAxisCount = 0;
|
||||||
|
|
||||||
bool getAccelerometerCalibrationAxisStatus(int axis)
|
bool accGetCalibrationAxisStatus(int axis)
|
||||||
{
|
{
|
||||||
if (isAccelerationCalibrationComplete()) {
|
if (accIsCalibrationComplete()) {
|
||||||
if (STATE(ACCELEROMETER_CALIBRATED)) {
|
if (STATE(ACCELEROMETER_CALIBRATED)) {
|
||||||
return true; // if calibration is valid - all axis are calibrated
|
return true; // if calibration is valid - all axis are calibrated
|
||||||
}
|
}
|
||||||
|
@ -311,11 +311,11 @@ bool getAccelerometerCalibrationAxisStatus(int axis)
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
uint8_t getAccelerometerCalibrationAxisFlags(void)
|
uint8_t accGetCalibrationAxisFlags(void)
|
||||||
{
|
{
|
||||||
uint8_t flags = 0;
|
uint8_t flags = 0;
|
||||||
for (int i = 0; i < 6; i++) {
|
for (int i = 0; i < 6; i++) {
|
||||||
if (getAccelerometerCalibrationAxisStatus(0)) {
|
if (accGetCalibrationAxisStatus(0)) {
|
||||||
flags |= (1 << i);
|
flags |= (1 << i);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -342,7 +342,7 @@ int getPrimaryAxisIndex(int32_t sample[3])
|
||||||
return -1;
|
return -1;
|
||||||
}
|
}
|
||||||
|
|
||||||
void performAcclerationCalibration(void)
|
static void performAcclerationCalibration(void)
|
||||||
{
|
{
|
||||||
int axisIndex = getPrimaryAxisIndex(acc.accADC);
|
int axisIndex = getPrimaryAxisIndex(acc.accADC);
|
||||||
|
|
||||||
|
@ -420,7 +420,7 @@ static void applyAccelerationZero(const flightDynamicsTrims_t * accZero, const f
|
||||||
acc.accADC[Z] = (acc.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 accUpdate(void)
|
||||||
{
|
{
|
||||||
if (!acc.dev.read(&acc.dev)) {
|
if (!acc.dev.read(&acc.dev)) {
|
||||||
return;
|
return;
|
||||||
|
@ -436,7 +436,7 @@ void updateAccelerationReadings(void)
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
if (!isAccelerationCalibrationComplete()) {
|
if (!accIsCalibrationComplete()) {
|
||||||
performAcclerationCalibration();
|
performAcclerationCalibration();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -445,7 +445,7 @@ void updateAccelerationReadings(void)
|
||||||
alignSensors(acc.accADC, acc.dev.accAlign);
|
alignSensors(acc.accADC, acc.dev.accAlign);
|
||||||
}
|
}
|
||||||
|
|
||||||
void setAccelerationCalibrationValues(void)
|
void accSetCalibrationValues(void)
|
||||||
{
|
{
|
||||||
if ((accelerometerConfig()->accZero.raw[X] == 0) && (accelerometerConfig()->accZero.raw[Y] == 0) && (accelerometerConfig()->accZero.raw[Z] == 0) &&
|
if ((accelerometerConfig()->accZero.raw[X] == 0) && (accelerometerConfig()->accZero.raw[Y] == 0) && (accelerometerConfig()->accZero.raw[Z] == 0) &&
|
||||||
(accelerometerConfig()->accGain.raw[X] == 4096) && (accelerometerConfig()->accGain.raw[Y] == 4096) &&(accelerometerConfig()->accGain.raw[Z] == 4096)) {
|
(accelerometerConfig()->accGain.raw[X] == 4096) && (accelerometerConfig()->accGain.raw[Y] == 4096) &&(accelerometerConfig()->accGain.raw[Z] == 4096)) {
|
||||||
|
@ -456,7 +456,7 @@ void setAccelerationCalibrationValues(void)
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void setAccelerationFilter(void)
|
void accInitFilters(void)
|
||||||
{
|
{
|
||||||
if (acc.accTargetLooptime && accelerometerConfig()->acc_lpf_hz) {
|
if (acc.accTargetLooptime && accelerometerConfig()->acc_lpf_hz) {
|
||||||
for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) {
|
for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) {
|
||||||
|
@ -465,7 +465,7 @@ void setAccelerationFilter(void)
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
bool isAccelerometerHealthy(void)
|
bool accIsHealthy(void)
|
||||||
{
|
{
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
|
@ -56,11 +56,11 @@ typedef struct accelerometerConfig_s {
|
||||||
PG_DECLARE(accelerometerConfig_t, accelerometerConfig);
|
PG_DECLARE(accelerometerConfig_t, accelerometerConfig);
|
||||||
|
|
||||||
bool accInit(uint32_t accTargetLooptime);
|
bool accInit(uint32_t accTargetLooptime);
|
||||||
bool isAccelerationCalibrationComplete(void);
|
bool accIsCalibrationComplete(void);
|
||||||
void accSetCalibrationCycles(uint16_t calibrationCyclesRequired);
|
void accSetCalibrationCycles(uint16_t calibrationCyclesRequired);
|
||||||
void updateAccelerationReadings(void);
|
void accUpdate(void);
|
||||||
void setAccelerationCalibrationValues(void);
|
void accSetCalibrationValues(void);
|
||||||
void setAccelerationFilter(void);
|
void accInitFilters(void);
|
||||||
bool isAccelerometerHealthy(void);
|
bool accIsHealthy(void);
|
||||||
bool getAccelerometerCalibrationAxisStatus(int axis);
|
bool accGetCalibrationAxisStatus(int axis);
|
||||||
uint8_t getAccelerometerCalibrationAxisFlags(void);
|
uint8_t accGetCalibrationAxisFlags(void);
|
||||||
|
|
|
@ -166,7 +166,7 @@ bool baroInit(void)
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
bool isBaroCalibrationComplete(void)
|
bool baroIsCalibrationComplete(void)
|
||||||
{
|
{
|
||||||
return calibratingB == 0;
|
return calibratingB == 0;
|
||||||
}
|
}
|
||||||
|
@ -207,7 +207,7 @@ typedef enum {
|
||||||
BAROMETER_NEEDS_CALCULATION
|
BAROMETER_NEEDS_CALCULATION
|
||||||
} barometerState_e;
|
} barometerState_e;
|
||||||
|
|
||||||
bool isBaroReady(void)
|
bool baroIsReady(void)
|
||||||
{
|
{
|
||||||
return baroReady;
|
return baroReady;
|
||||||
}
|
}
|
||||||
|
@ -249,7 +249,7 @@ static void performBaroCalibrationCycle(void)
|
||||||
|
|
||||||
int32_t baroCalculateAltitude(void)
|
int32_t baroCalculateAltitude(void)
|
||||||
{
|
{
|
||||||
if (!isBaroCalibrationComplete()) {
|
if (!baroIsCalibrationComplete()) {
|
||||||
performBaroCalibrationCycle();
|
performBaroCalibrationCycle();
|
||||||
baro.BaroAlt = 0;
|
baro.BaroAlt = 0;
|
||||||
}
|
}
|
||||||
|
@ -269,7 +269,7 @@ int32_t baroCalculateAltitude(void)
|
||||||
return baro.BaroAlt;
|
return baro.BaroAlt;
|
||||||
}
|
}
|
||||||
|
|
||||||
bool isBarometerHealthy(void)
|
bool baroIsHealthy(void)
|
||||||
{
|
{
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
|
@ -47,9 +47,9 @@ typedef struct baro_s {
|
||||||
extern baro_t baro;
|
extern baro_t baro;
|
||||||
|
|
||||||
bool baroInit(void);
|
bool baroInit(void);
|
||||||
bool isBaroCalibrationComplete(void);
|
bool baroIsCalibrationComplete(void);
|
||||||
void baroSetCalibrationCycles(uint16_t calibrationCyclesRequired);
|
void baroSetCalibrationCycles(uint16_t calibrationCyclesRequired);
|
||||||
uint32_t baroUpdate(void);
|
uint32_t baroUpdate(void);
|
||||||
bool isBaroReady(void);
|
bool baroIsReady(void);
|
||||||
int32_t baroCalculateAltitude(void);
|
int32_t baroCalculateAltitude(void);
|
||||||
bool isBarometerHealthy(void);
|
bool baroIsHealthy(void);
|
||||||
|
|
|
@ -96,7 +96,7 @@ static void updateBatteryVoltage(uint32_t vbatTimeDelta)
|
||||||
/* Batt Hysteresis of +/-100mV */
|
/* Batt Hysteresis of +/-100mV */
|
||||||
#define VBATT_HYSTERESIS 1
|
#define VBATT_HYSTERESIS 1
|
||||||
|
|
||||||
void updateBattery(uint32_t vbatTimeDelta)
|
void batteryUpdate(uint32_t vbatTimeDelta)
|
||||||
{
|
{
|
||||||
updateBatteryVoltage(vbatTimeDelta);
|
updateBatteryVoltage(vbatTimeDelta);
|
||||||
|
|
||||||
|
@ -166,13 +166,6 @@ batteryState_e getBatteryState(void)
|
||||||
return batteryState;
|
return batteryState;
|
||||||
}
|
}
|
||||||
|
|
||||||
const char * const batteryStateStrings[] = {"OK", "WARNING", "CRITICAL", "NOT PRESENT"};
|
|
||||||
|
|
||||||
const char * getBatteryStateString(void)
|
|
||||||
{
|
|
||||||
return batteryStateStrings[batteryState];
|
|
||||||
}
|
|
||||||
|
|
||||||
void batteryInit(void)
|
void batteryInit(void)
|
||||||
{
|
{
|
||||||
batteryState = BATTERY_NOT_PRESENT;
|
batteryState = BATTERY_NOT_PRESENT;
|
||||||
|
@ -192,7 +185,7 @@ int32_t currentSensorToCentiamps(uint16_t src)
|
||||||
return (millivolts * 1000) / (int32_t)batteryConfig()->currentMeterScale; // current in 0.01A steps
|
return (millivolts * 1000) / (int32_t)batteryConfig()->currentMeterScale; // current in 0.01A steps
|
||||||
}
|
}
|
||||||
|
|
||||||
void updateCurrentMeter(int32_t lastUpdateAt, uint16_t deadband3d_throttle)
|
void currentMeterUpdate(int32_t lastUpdateAt, uint16_t deadband3d_throttle)
|
||||||
{
|
{
|
||||||
static int32_t amperageRaw = 0;
|
static int32_t amperageRaw = 0;
|
||||||
static int64_t mAhdrawnRaw = 0;
|
static int64_t mAhdrawnRaw = 0;
|
||||||
|
|
|
@ -71,11 +71,10 @@ extern int32_t mAhDrawn;
|
||||||
|
|
||||||
uint16_t batteryAdcToVoltage(uint16_t src);
|
uint16_t batteryAdcToVoltage(uint16_t src);
|
||||||
batteryState_e getBatteryState(void);
|
batteryState_e getBatteryState(void);
|
||||||
const char * getBatteryStateString(void);
|
void batteryUpdate(uint32_t vbatTimeDelta);
|
||||||
void updateBattery(uint32_t vbatTimeDelta);
|
|
||||||
void batteryInit(void);
|
void batteryInit(void);
|
||||||
|
|
||||||
void updateCurrentMeter(int32_t lastUpdateAt, uint16_t deadband3d_throttle);
|
void currentMeterUpdate(int32_t lastUpdateAt, uint16_t deadband3d_throttle);
|
||||||
int32_t currentMeterToCentiamps(uint16_t src);
|
int32_t currentMeterToCentiamps(uint16_t src);
|
||||||
|
|
||||||
uint8_t calculateBatteryPercentage(void);
|
uint8_t calculateBatteryPercentage(void);
|
||||||
|
|
|
@ -37,7 +37,7 @@ hardwareSensorStatus_e getHwAccelerometerStatus(void)
|
||||||
{
|
{
|
||||||
#if defined(ACC)
|
#if defined(ACC)
|
||||||
if (detectedSensors[SENSOR_INDEX_ACC] != ACC_NONE) {
|
if (detectedSensors[SENSOR_INDEX_ACC] != ACC_NONE) {
|
||||||
if (isAccelerometerHealthy()) {
|
if (accIsHealthy()) {
|
||||||
return HW_SENSOR_OK;
|
return HW_SENSOR_OK;
|
||||||
}
|
}
|
||||||
else {
|
else {
|
||||||
|
@ -89,7 +89,7 @@ hardwareSensorStatus_e getHwBarometerStatus(void)
|
||||||
{
|
{
|
||||||
#if defined(BARO)
|
#if defined(BARO)
|
||||||
if (detectedSensors[SENSOR_INDEX_BARO] != BARO_NONE) {
|
if (detectedSensors[SENSOR_INDEX_BARO] != BARO_NONE) {
|
||||||
if (isBarometerHealthy()) {
|
if (baroIsHealthy()) {
|
||||||
return HW_SENSOR_OK;
|
return HW_SENSOR_OK;
|
||||||
}
|
}
|
||||||
else {
|
else {
|
||||||
|
@ -115,7 +115,7 @@ hardwareSensorStatus_e getHwRangefinderStatus(void)
|
||||||
{
|
{
|
||||||
#if defined(SONAR)
|
#if defined(SONAR)
|
||||||
if (detectedSensors[SENSOR_INDEX_RANGEFINDER] != RANGEFINDER_NONE) {
|
if (detectedSensors[SENSOR_INDEX_RANGEFINDER] != RANGEFINDER_NONE) {
|
||||||
if (isRangefinderHealthy()) {
|
if (rangefinderIsHealthy()) {
|
||||||
return HW_SENSOR_OK;
|
return HW_SENSOR_OK;
|
||||||
}
|
}
|
||||||
else {
|
else {
|
||||||
|
@ -141,7 +141,7 @@ hardwareSensorStatus_e getHwPitotmeterStatus(void)
|
||||||
{
|
{
|
||||||
#if defined(PITOT)
|
#if defined(PITOT)
|
||||||
if (detectedSensors[SENSOR_INDEX_PITOT] != PITOT_NONE) {
|
if (detectedSensors[SENSOR_INDEX_PITOT] != PITOT_NONE) {
|
||||||
if (isPitotmeterHealthy()) {
|
if (pitotIsHealthy()) {
|
||||||
return HW_SENSOR_OK;
|
return HW_SENSOR_OK;
|
||||||
}
|
}
|
||||||
else {
|
else {
|
||||||
|
|
|
@ -118,7 +118,7 @@ bool pitotInit(void)
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
bool isPitotCalibrationComplete(void)
|
bool pitotIsCalibrationComplete(void)
|
||||||
{
|
{
|
||||||
return calibratingP == 0;
|
return calibratingP == 0;
|
||||||
}
|
}
|
||||||
|
@ -160,7 +160,7 @@ typedef enum {
|
||||||
} pitotmeterState_e;
|
} pitotmeterState_e;
|
||||||
|
|
||||||
|
|
||||||
bool isPitotReady(void) {
|
bool pitotIsReady(void) {
|
||||||
return pitotReady;
|
return pitotReady;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -202,10 +202,7 @@ static void performPitotCalibrationCycle(void)
|
||||||
|
|
||||||
int32_t pitotCalculateAirSpeed(void)
|
int32_t pitotCalculateAirSpeed(void)
|
||||||
{
|
{
|
||||||
if (!isPitotCalibrationComplete()) {
|
if (pitotIsCalibrationComplete()) {
|
||||||
performPitotCalibrationCycle();
|
|
||||||
pitot.airSpeed = 0;
|
|
||||||
} else {
|
|
||||||
const float CalibratedAirspeed_tmp = pitotmeterConfig()->pitot_scale * CASFACTOR * sqrtf(powf(fabsf(pitotPressure - pitotPressureZero) / P0 + 1.0f, CCEXPONENT) - 1.0f);
|
const float CalibratedAirspeed_tmp = pitotmeterConfig()->pitot_scale * CASFACTOR * sqrtf(powf(fabsf(pitotPressure - pitotPressureZero) / P0 + 1.0f, CCEXPONENT) - 1.0f);
|
||||||
CalibratedAirspeed = CalibratedAirspeed * pitotmeterConfig()->pitot_noise_lpf + CalibratedAirspeed_tmp * (1.0f - pitotmeterConfig()->pitot_noise_lpf); // additional LPF to reduce baro noise
|
CalibratedAirspeed = CalibratedAirspeed * pitotmeterConfig()->pitot_noise_lpf + CalibratedAirspeed_tmp * (1.0f - pitotmeterConfig()->pitot_noise_lpf); // additional LPF to reduce baro noise
|
||||||
float TrueAirspeed = CalibratedAirspeed * TASFACTOR * sqrtf(pitotTemperature);
|
float TrueAirspeed = CalibratedAirspeed * TASFACTOR * sqrtf(pitotTemperature);
|
||||||
|
@ -215,11 +212,14 @@ int32_t pitotCalculateAirSpeed(void)
|
||||||
//debug[1] = (int16_t)(TrueAirspeed*100);
|
//debug[1] = (int16_t)(TrueAirspeed*100);
|
||||||
//debug[2] = (int16_t)((pitotTemperature-273.15f)*100);
|
//debug[2] = (int16_t)((pitotTemperature-273.15f)*100);
|
||||||
//debug[3] = AirSpeed;
|
//debug[3] = AirSpeed;
|
||||||
|
} else {
|
||||||
|
performPitotCalibrationCycle();
|
||||||
|
pitot.airSpeed = 0;
|
||||||
}
|
}
|
||||||
return pitot.airSpeed;
|
return pitot.airSpeed;
|
||||||
}
|
}
|
||||||
|
|
||||||
bool isPitotmeterHealthy(void)
|
bool pitotIsHealthy(void)
|
||||||
{
|
{
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
|
@ -48,9 +48,9 @@ typedef struct pito_s {
|
||||||
extern pitot_t pitot;
|
extern pitot_t pitot;
|
||||||
|
|
||||||
bool pitotInit(void);
|
bool pitotInit(void);
|
||||||
bool isPitotCalibrationComplete(void);
|
bool pitotIsCalibrationComplete(void);
|
||||||
void pitotSetCalibrationCycles(uint16_t calibrationCyclesRequired);
|
void pitotSetCalibrationCycles(uint16_t calibrationCyclesRequired);
|
||||||
uint32_t pitotUpdate(void);
|
uint32_t pitotUpdate(void);
|
||||||
bool isPitotReady(void);
|
bool pitotIsReady(void);
|
||||||
int32_t pitotCalculateAirSpeed(void);
|
int32_t pitotCalculateAirSpeed(void);
|
||||||
bool isPitotmeterHealthy(void);
|
bool pitotIsHealthy(void);
|
||||||
|
|
|
@ -243,7 +243,7 @@ int32_t rangefinderGetLatestAltitude(void)
|
||||||
return calculatedAltitude;
|
return calculatedAltitude;
|
||||||
}
|
}
|
||||||
|
|
||||||
bool isRangefinderHealthy(void)
|
bool rangefinderIsHealthy(void)
|
||||||
{
|
{
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue