Skip to content

Commit

Permalink
Couple fixes
Browse files Browse the repository at this point in the history
  • Loading branch information
shellixyz committed Jan 29, 2019
1 parent e810cc6 commit 3a83118
Show file tree
Hide file tree
Showing 7 changed files with 83 additions and 48 deletions.
14 changes: 14 additions & 0 deletions src/main/blackbox/blackbox.c
Original file line number Diff line number Diff line change
Expand Up @@ -466,8 +466,12 @@ typedef struct blackboxSlowState_s {
uint16_t sagCompensatedVBat;
int16_t wind[XYZ_AXIS_COUNT];
int16_t mpuTemperature;
#ifdef USE_BARO
int16_t baroTemperature;
#endif
#ifdef USE_TEMPERATURE_SENSOR
int16_t tempSensorTemperature[MAX_TEMP_SENSORS];
#endif
} __attribute__((__packed__)) blackboxSlowState_t; // We pack this struct so that padding doesn't interfere with memcmp()

//From rc_controls.c
Expand Down Expand Up @@ -1056,9 +1060,14 @@ static void writeSlowFrame(void)
blackboxWriteSigned16VBArray(slowHistory.wind, XYZ_AXIS_COUNT);

blackboxWriteSignedVB(slowHistory.mpuTemperature);

#ifdef USE_BARO
blackboxWriteSignedVB(slowHistory.baroTemperature);
#endif

#ifdef USE_TEMPERATURE_SENSOR
blackboxWriteSigned16VBArray(slowHistory.tempSensorTemperature, MAX_TEMP_SENSORS);
#endif

blackboxSlowFrameIterationTimer = 0;
}
Expand Down Expand Up @@ -1095,13 +1104,18 @@ static void loadSlowState(blackboxSlowState_t *slow)
bool valid_temp;
valid_temp = getMPUTemperature(&slow->mpuTemperature);
if (!valid_temp) slow->mpuTemperature = 0xFFFF;

#ifdef USE_BARO
valid_temp = getBaroTemperature(&slow->baroTemperature);
if (!valid_temp) slow->baroTemperature = 0xFFFF;
#endif

#ifdef USE_TEMPERATURE_SENSOR
for (uint8_t index; index < MAX_TEMP_SENSORS; ++index) {
valid_temp = getSensorTemperature(index, slow->tempSensorTemperature + index);
if (!valid_temp) slow->tempSensorTemperature[index] = 0xFFFF;
}
#endif

}

Expand Down
7 changes: 7 additions & 0 deletions src/main/fc/fc_msp.c
Original file line number Diff line number Diff line change
Expand Up @@ -1350,8 +1350,13 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF
sbufWriteU16(dst, osdConfig()->neg_alt_alarm);
sbufWriteU16(dst, osdConfig()->mpu_temp_alarm_min);
sbufWriteU16(dst, osdConfig()->mpu_temp_alarm_max);
#ifdef USE_BARO
sbufWriteU16(dst, osdConfig()->baro_temp_alarm_min);
sbufWriteU16(dst, osdConfig()->baro_temp_alarm_max);
#else
sbufWriteU16(dst, 0);
sbufWriteU16(dst, 0);
#endif
break;

case MSP2_INAV_OSD_PREFERENCES:
Expand Down Expand Up @@ -2602,8 +2607,10 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src)
osdConfigMutable()->neg_alt_alarm = sbufReadU16(src);
osdConfigMutable()->mpu_temp_alarm_min = sbufReadU16(src);
osdConfigMutable()->mpu_temp_alarm_max = sbufReadU16(src);
#ifdef USE_BARO
osdConfigMutable()->baro_temp_alarm_min = sbufReadU16(src);
osdConfigMutable()->baro_temp_alarm_max = sbufReadU16(src);
#endif
} else
return MSP_RESULT_ERROR;
}
Expand Down
10 changes: 10 additions & 0 deletions src/main/fc/settings.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -1600,6 +1600,16 @@ groups:
field: mpu_temp_alarm_max
min: -55
max: 125
- name: osd_baro_temp_alarm_min
field: baro_temp_alarm_min
condition: USE_BARO
min: -55
max: 125
- name: osd_baro_temp_alarm_max
field: baro_temp_alarm_max
condition: USE_BARO
min: -55
max: 125

- name: osd_artificial_horizon_reverse_roll
field: ahi_reverse_roll
Expand Down
2 changes: 2 additions & 0 deletions src/main/io/osd.c
Original file line number Diff line number Diff line change
Expand Up @@ -2671,8 +2671,10 @@ void pgResetFn_osdConfig(osdConfig_t *osdConfig)
osdConfig->neg_alt_alarm = 5;
osdConfig->mpu_temp_alarm_min = -200;
osdConfig->mpu_temp_alarm_max = 600;
#ifdef USE_BARO
osdConfig->baro_temp_alarm_min = -200;
osdConfig->baro_temp_alarm_max = 600;
#endif

osdConfig->video_system = VIDEO_SYSTEM_AUTO;

Expand Down
5 changes: 4 additions & 1 deletion src/main/rx/eleres.c
Original file line number Diff line number Diff line change
Expand Up @@ -272,8 +272,11 @@ static void telemetryRX(void)

presfil -= presfil/4;
presfil += baro.baroPressure;

int16_t temperature;
getMPUTemperature(&temperature);
thempfil -= thempfil/8;
thempfil += DEGREES_TO_DECIDEGREES(getCurrentTemperature());
thempfil += temperature;

switch (telem_state++) {
case 0:
Expand Down
79 changes: 40 additions & 39 deletions src/main/sensors/temperature.c
Original file line number Diff line number Diff line change
Expand Up @@ -53,9 +53,9 @@ PG_REGISTER_ARRAY(tempSensorConfig_t, MAX_TEMP_SENSORS, tempSensorConfig, PG_TEM
static uint16_t mpuTemperature, baroTemperature;
static uint8_t mpuBaroTempValid = 0;

#ifdef USE_TEMPERATURE_SENSOR
static int16_t tempSensorValue[MAX_TEMP_SENSORS];

#ifdef USE_TEMPERATURE_SENSOR
// Each bit corresponds to a sensor LSB = first sensor. 1 = valid value
static uint8_t sensorStatus[MAX_TEMP_SENSORS / 8 + (MAX_TEMP_SENSORS % 8 ? 1 : 0)];

Expand Down Expand Up @@ -123,7 +123,7 @@ void temperatureInit(void)
switch (configSlot->type) {
#ifdef DS18B20_DRIVER_AVAILABLE
case TEMP_SENSOR_DS18B20:
tempSensorValue[configIndex] = -125;
tempSensorValue[configIndex] = -1250;
ds18b20_configure(configSlot->address, DS18B20_CONFIG_9BIT);
break;
#endif
Expand All @@ -133,15 +133,46 @@ void temperatureInit(void)
}
}

#endif

static bool temperatureSensorValueIsValid(uint8_t sensorIndex)
{
uint8_t mask = 1 << (sensorIndex % 8);
uint8_t byteIndex = sensorIndex / 8;
return sensorStatus[byteIndex] & mask;
}

bool getSensorTemperature(uint8_t sensorIndex, int16_t *temperature)
{
*temperature = tempSensorValue[sensorIndex];
return temperatureSensorValueIsValid(sensorIndex);
}

void tempSensorAddressToString(uint64_t address, char *hex_address)
{
if (address < 8)
tfp_sprintf(hex_address, "%d", address);
else {
uint32_t *address32 = (uint32_t *)&address;
tfp_sprintf(hex_address, "%08lx%08lx", address32[1], address32[0]);
}
}

bool tempSensorStringToAddress(const char *hex_address, uint64_t *address)
{
uint16_t char_count = 0;
*address = 0;
while (*hex_address && (*hex_address != ' ')) {
if (++char_count > 16) return false;
char byte = *hex_address++;
if (byte >= '0' && byte <= '9') byte = byte - '0';
else if (byte >= 'a' && byte <='f') byte = byte - 'a' + 10;
else if (byte >= 'A' && byte <='F') byte = byte - 'A' + 10;
else return false;
*address = (*address << 4) | (byte & 0xF);
}
return true;
}
#endif /* USE_TEMPERATURE_SENSOR */

void temperatureUpdate(void)
{

Expand All @@ -159,6 +190,7 @@ void temperatureUpdate(void)
mpuBaroTempValid &= ~(1 << BARO_TEMP_VALID_BIT);
#endif

#ifdef USE_TEMPERATURE_SENSOR
for (uint8_t sensorIndex = 0; sensorIndex < MAX_TEMP_SENSORS; ++sensorIndex) {
const tempSensorConfig_t *configSlot = tempSensorConfig(sensorIndex);
bool valueValid = false;
Expand All @@ -178,14 +210,14 @@ void temperatureUpdate(void)
#ifdef DS18B20_DRIVER_AVAILABLE
int16_t temperature;
if (ds18b20_read_temperature(configSlot->address, &temperature)) {
if (temperatureSensorValueIsValid(sensorIndex) || (tempSensorValue[sensorIndex] == -124)) {
if (temperatureSensorValueIsValid(sensorIndex) || (tempSensorValue[sensorIndex] == -1240)) {
tempSensorValue[sensorIndex] = temperature;
valueValid = true;
} else
tempSensorValue[sensorIndex] = -124;
tempSensorValue[sensorIndex] = -1240;

} else
tempSensorValue[sensorIndex] = -125;
tempSensorValue[sensorIndex] = -1250;
#endif
break;

Expand All @@ -200,6 +232,7 @@ void temperatureUpdate(void)
sensorStatus[byteIndex] &= ~statusMask;

}
#endif

#ifdef DS18B20_DRIVER_AVAILABLE
ds18b20_start_conversion();
Expand All @@ -218,38 +251,6 @@ bool getBaroTemperature(int16_t *temperature)
return BARO_TEMP_VALID;
}

bool getSensorTemperature(uint8_t sensorIndex, int16_t *temperature)
{
*temperature = tempSensorValue[sensorIndex];
return temperatureSensorValueIsValid(sensorIndex);
}

void tempSensorAddressToString(uint64_t address, char *hex_address)
{
if (address < 8)
tfp_sprintf(hex_address, "%d", address);
else {
uint32_t *address32 = (uint32_t *)&address;
tfp_sprintf(hex_address, "%08lx%08lx", address32[1], address32[0]);
}
}

bool tempSensorStringToAddress(const char *hex_address, uint64_t *address)
{
uint16_t char_count = 0;
*address = 0;
while (*hex_address && (*hex_address != ' ')) {
if (++char_count > 16) return false;
char byte = *hex_address++;
if (byte >= '0' && byte <= '9') byte = byte - '0';
else if (byte >= 'a' && byte <='f') byte = byte - 'a' + 10;
else if (byte >= 'A' && byte <='F') byte = byte - 'A' + 10;
else return false;
*address = (*address << 4) | (byte & 0xF);
}
return true;
}

void resetTempSensorConfig(void)
{
memset(tempSensorConfigMutable(0), 0, sizeof(tempSensorConfig_t) * MAX_TEMP_SENSORS);
Expand Down
14 changes: 6 additions & 8 deletions src/main/sensors/temperature.h
Original file line number Diff line number Diff line change
Expand Up @@ -24,8 +24,6 @@

typedef enum {
TEMP_SENSOR_NONE = 0,
TEMP_SENSOR_MPU,
TEMP_SENSOR_BARO,
TEMP_SENSOR_LM75,
TEMP_SENSOR_DS18B20
} tempSensorType_e;
Expand All @@ -43,15 +41,15 @@ PG_DECLARE_ARRAY(tempSensorConfig_t, MAX_TEMP_SENSORS, tempSensorConfig);
// Temperature is returned in degC*10
bool getMPUTemperature(int16_t *temperature);
bool getBaroTemperature(int16_t *temperature);
bool getSensorTemperature(uint8_t sensorIndex, int16_t *temperature);
void temperatureUpdate(void);

#ifdef USE_TEMPERATURE_SENSOR
void temperatureInit(void);

bool getSensorTemperature(uint8_t sensorIndex, int16_t *temperature);

void tempSensorAddressToString(uint64_t address, char *hex_address);
bool tempSensorStringToAddress(const char *hex_address, uint64_t *address);
//uint64_t tempSensorStringToAddress(const char *hex_address);
#endif

void resetTempSensorConfig(void);

#ifdef USE_TEMPERATURE_SENSOR
void temperatureInit(void);
#endif

0 comments on commit 3a83118

Please sign in to comment.