Skip to content

Commit

Permalink
Rebase on #3981
Browse files Browse the repository at this point in the history
Addition of source temperature sensor's index
  • Loading branch information
nmaggioni committed Nov 5, 2018
1 parent 471d6e5 commit 6347696
Show file tree
Hide file tree
Showing 3 changed files with 14 additions and 5 deletions.
12 changes: 8 additions & 4 deletions src/main/blackbox/blackbox.c
Original file line number Diff line number Diff line change
Expand Up @@ -346,7 +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)},
{"gyroTemperature", -1, SIGNED, PREDICT(0), ENCODING(UNSIGNED_VB)},
{"temperature", -1, SIGNED, PREDICT(0), ENCODING(UNSIGNED_VB)},
{"temperatureSource", -1, UNSIGNED, PREDICT(0), ENCODING(UNSIGNED_VB)},
};

typedef enum BlackboxState {
Expand Down Expand Up @@ -445,7 +446,8 @@ typedef struct blackboxSlowState_s {
uint16_t powerSupplyImpedance;
uint16_t sagCompensatedVBat;
int16_t wind[XYZ_AXIS_COUNT];
int16_t gyroTemperature;
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
Expand Down Expand Up @@ -1033,7 +1035,8 @@ static void writeSlowFrame(void)

blackboxWriteSigned16VBArray(slowHistory.wind, XYZ_AXIS_COUNT);

blackboxWriteSignedVB(slowHistory.gyroTemperature);
blackboxWriteSignedVB(slowHistory.temperature);
blackboxWriteSignedVB(slowHistory.temperatureSource);

blackboxSlowFrameIterationTimer = 0;
}
Expand Down Expand Up @@ -1066,7 +1069,8 @@ static void loadSlowState(blackboxSlowState_t *slow)
slow->wind[i] = 0;
#endif

slow->gyroTemperature = getTemperature(TEMP_GYRO);
slow->temperature = getCurrentTemperature();
slow->temperatureSource = getCurrentTemperatureSensorUsed();
}

}
Expand Down
6 changes: 5 additions & 1 deletion src/main/sensors/temperature.c
Original file line number Diff line number Diff line change
Expand Up @@ -45,14 +45,18 @@ float getCurrentTemperature(void)
return tempSensorValue[tempSensorValid]/10.0f;
}

tempSensor_e getCurrentTemperatureSensorUsed(void) {
return tempSensorValid;
}

void temperatureUpdate(void)
{
// TEMP_GYRO: Update gyro temperature in decidegrees
if (gyroReadTemperature()) {
tempSensorValue[TEMP_GYRO] = gyroGetTemperature();
tempSensorValid = TEMP_GYRO;
}

#if defined(USE_BARO)
// TEMP_BARO: Update baro temperature in decidegrees
if(sensors(SENSOR_BARO)){
Expand Down
1 change: 1 addition & 0 deletions src/main/sensors/temperature.h
Original file line number Diff line number Diff line change
Expand Up @@ -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);

0 comments on commit 6347696

Please sign in to comment.