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

Merge pull request #3979 from nmaggioni/blackbox_temperature

Gyro temperature in blackbox
This commit is contained in:
Konstantin Sharlaimov 2018-11-24 21:29:28 +01:00 committed by GitHub
commit f49decfb54
No known key found for this signature in database
GPG key ID: 4AEE18F83AFDEB23
3 changed files with 17 additions and 1 deletions

View file

@ -76,6 +76,7 @@
#include "sensors/rangefinder.h"
#include "sensors/sensors.h"
#include "flight/wind_estimator.h"
#include "sensors/temperature.h"
#if defined(ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT)
@ -345,6 +346,8 @@ static const blackboxSimpleFieldDefinition_t blackboxSlowFields[] = {
{"wind", 0, SIGNED, PREDICT(0), ENCODING(UNSIGNED_VB)},
{"wind", 1, SIGNED, PREDICT(0), ENCODING(UNSIGNED_VB)},
{"wind", 2, SIGNED, PREDICT(0), ENCODING(UNSIGNED_VB)},
{"temperature", -1, SIGNED, PREDICT(0), ENCODING(SIGNED_VB)},
{"temperatureSource", -1, UNSIGNED, PREDICT(0), ENCODING(UNSIGNED_VB)},
};
typedef enum BlackboxState {
@ -443,6 +446,8 @@ typedef struct blackboxSlowState_s {
uint16_t powerSupplyImpedance;
uint16_t sagCompensatedVBat;
int16_t wind[XYZ_AXIS_COUNT];
int16_t temperature;
uint8_t temperatureSource;
} __attribute__((__packed__)) blackboxSlowState_t; // We pack this struct so that padding doesn't interfere with memcmp()
//From rc_controls.c
@ -1030,6 +1035,9 @@ static void writeSlowFrame(void)
blackboxWriteSigned16VBArray(slowHistory.wind, XYZ_AXIS_COUNT);
blackboxWriteSignedVB(slowHistory.temperature);
blackboxWriteUnsignedVB(slowHistory.temperatureSource);
blackboxSlowFrameIterationTimer = 0;
}
@ -1060,6 +1068,9 @@ static void loadSlowState(blackboxSlowState_t *slow)
#else
slow->wind[i] = 0;
#endif
slow->temperature = (int) getCurrentTemperature() * 10;
slow->temperatureSource = getCurrentTemperatureSensorUsed();
}
}

View file

@ -45,6 +45,10 @@ float getCurrentTemperature(void)
return tempSensorValue[tempSensorValid]/10.0f;
}
tempSensor_e getCurrentTemperatureSensorUsed(void) {
return tempSensorValid;
}
void temperatureUpdate(void)
{
// TEMP_GYRO: Update gyro temperature in decidegrees
@ -52,7 +56,7 @@ void temperatureUpdate(void)
tempSensorValue[TEMP_GYRO] = gyroGetTemperature();
tempSensorValid = TEMP_GYRO;
}
#if defined(USE_BARO)
// TEMP_BARO: Update baro temperature in decidegrees
if(sensors(SENSOR_BARO)){

View file

@ -28,4 +28,5 @@ typedef enum {
// Temperature is returned in degC*10
int16_t getTemperature(tempSensor_e sensor);
float getCurrentTemperature(void);
tempSensor_e getCurrentTemperatureSensorUsed(void);
void temperatureUpdate(void);