diff --git a/src/main/blackbox/blackbox.c b/src/main/blackbox/blackbox.c index 885addcc37f..0557e7a0b98 100644 --- a/src/main/blackbox/blackbox.c +++ b/src/main/blackbox/blackbox.c @@ -353,19 +353,19 @@ 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)}, - {"MPU temperature", -1, SIGNED, PREDICT(0), ENCODING(SIGNED_VB)}, + {"IMUTemperature", -1, SIGNED, PREDICT(0), ENCODING(SIGNED_VB)}, #ifdef USE_BARO - {"baro temperature", -1, SIGNED, PREDICT(0), ENCODING(SIGNED_VB)}, + {"baroTemperature", -1, SIGNED, PREDICT(0), ENCODING(SIGNED_VB)}, #endif #ifdef USE_TEMPERATURE_SENSOR - {"temp0 temperature", -1, SIGNED, PREDICT(0), ENCODING(SIGNED_VB)}, - {"temp1 temperature", -1, SIGNED, PREDICT(0), ENCODING(SIGNED_VB)}, - {"temp2 temperature", -1, SIGNED, PREDICT(0), ENCODING(SIGNED_VB)}, - {"temp3 temperature", -1, SIGNED, PREDICT(0), ENCODING(SIGNED_VB)}, - {"temp4 temperature", -1, SIGNED, PREDICT(0), ENCODING(SIGNED_VB)}, - {"temp5 temperature", -1, SIGNED, PREDICT(0), ENCODING(SIGNED_VB)}, - {"temp6 temperature", -1, SIGNED, PREDICT(0), ENCODING(SIGNED_VB)}, - {"temp7 temperature", -1, SIGNED, PREDICT(0), ENCODING(SIGNED_VB)}, + {"sens0Temp", -1, SIGNED, PREDICT(0), ENCODING(SIGNED_VB)}, + {"sens1Temp", -1, SIGNED, PREDICT(0), ENCODING(SIGNED_VB)}, + {"sens2Temp", -1, SIGNED, PREDICT(0), ENCODING(SIGNED_VB)}, + {"sens3Temp", -1, SIGNED, PREDICT(0), ENCODING(SIGNED_VB)}, + {"sens4Temp", -1, SIGNED, PREDICT(0), ENCODING(SIGNED_VB)}, + {"sens5Temp", -1, SIGNED, PREDICT(0), ENCODING(SIGNED_VB)}, + {"sens6Temp", -1, SIGNED, PREDICT(0), ENCODING(SIGNED_VB)}, + {"sens7Temp", -1, SIGNED, PREDICT(0), ENCODING(SIGNED_VB)}, #endif }; @@ -465,9 +465,13 @@ typedef struct blackboxSlowState_s { uint16_t powerSupplyImpedance; uint16_t sagCompensatedVBat; int16_t wind[XYZ_AXIS_COUNT]; - int16_t mpuTemperature; + int16_t imuTemperature; +#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 @@ -1055,10 +1059,15 @@ static void writeSlowFrame(void) blackboxWriteSigned16VBArray(slowHistory.wind, XYZ_AXIS_COUNT); - blackboxWriteSignedVB(slowHistory.mpuTemperature); + blackboxWriteSignedVB(slowHistory.imuTemperature); + +#ifdef USE_BARO blackboxWriteSignedVB(slowHistory.baroTemperature); +#endif +#ifdef USE_TEMPERATURE_SENSOR blackboxWriteSigned16VBArray(slowHistory.tempSensorTemperature, MAX_TEMP_SENSORS); +#endif blackboxSlowFrameIterationTimer = 0; } @@ -1093,15 +1102,20 @@ static void loadSlowState(blackboxSlowState_t *slow) } bool valid_temp; - valid_temp = getMPUTemperature(&slow->mpuTemperature); - if (!valid_temp) slow->mpuTemperature = 0xFFFF; + valid_temp = getIMUTemperature(&slow->imuTemperature); + if (!valid_temp) slow->imuTemperature = 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 } diff --git a/src/main/cms/cms_menu_osd.c b/src/main/cms/cms_menu_osd.c index 9ee93ddbb88..7690b5aec32 100755 --- a/src/main/cms/cms_menu_osd.c +++ b/src/main/cms/cms_menu_osd.c @@ -245,7 +245,7 @@ static const OSD_Entry menuOsdElemsEntries[] = OSD_ELEMENT_ENTRY("WIND HOR", OSD_WIND_SPEED_HORIZONTAL), OSD_ELEMENT_ENTRY("WIND VERT", OSD_WIND_SPEED_VERTICAL), - OSD_ELEMENT_ENTRY("MPU TEMP", OSD_MPU_TEMPERATURE), + OSD_ELEMENT_ENTRY("IMU TEMP", OSD_IMU_TEMPERATURE), #ifdef USE_BARO OSD_ELEMENT_ENTRY("BARO TEMP", OSD_BARO_TEMPERATURE), #endif diff --git a/src/main/drivers/1-wire/ds2482.c b/src/main/drivers/1-wire/ds2482.c index 95dec470ad3..e1c4b60a83f 100644 --- a/src/main/drivers/1-wire/ds2482.c +++ b/src/main/drivers/1-wire/ds2482.c @@ -89,23 +89,20 @@ bool ds2482_write_config(_1WireDev_t *_1WireDev, uint8_t config) return busWrite(_1WireDev->busDev, DS2482_WRITE_CONFIG_CMD, DS2482_CONFIG_WRITE_BYTE(config)); } -bool ds2482_wait_for_bus(_1WireDev_t *_1WireDev) +bool ds2482_poll(_1WireDev_t *_1WireDev, bool wait_for_bus, uint8_t *status) { - uint8_t status; + uint8_t status_temp; do { - bool ack = busRead(_1WireDev->busDev, 0xFF, &status); + bool ack = busRead(_1WireDev->busDev, 0xFF, &status_temp); if (!ack) return false; - } while (DS2482_1WIRE_BUSY(status)); + } while (wait_for_bus && DS2482_1WIRE_BUSY(status_temp)); + if (status) *status = status_temp; return true; } -bool ds2482_poll(_1WireDev_t *_1WireDev, bool wait_for_bus, uint8_t *status) +bool ds2482_wait_for_bus(_1WireDev_t *_1WireDev) { - do { - bool ack = busRead(_1WireDev->busDev, 0xFF, status); - if (!ack) return false; - } while (wait_for_bus && DS2482_1WIRE_BUSY(*status)); - return true; + return ds2482_poll(_1WireDev, true, NULL); } bool ds2482_1wire_reset(_1WireDev_t *_1WireDev) diff --git a/src/main/fc/fc_msp.c b/src/main/fc/fc_msp.c index 68652f6a11c..11751bedc71 100644 --- a/src/main/fc/fc_msp.c +++ b/src/main/fc/fc_msp.c @@ -1348,10 +1348,15 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF sbufWriteU16(dst, osdConfig()->alt_alarm); sbufWriteU16(dst, osdConfig()->dist_alarm); sbufWriteU16(dst, osdConfig()->neg_alt_alarm); - sbufWriteU16(dst, osdConfig()->mpu_temp_alarm_min); - sbufWriteU16(dst, osdConfig()->mpu_temp_alarm_max); + sbufWriteU16(dst, osdConfig()->imu_temp_alarm_min); + sbufWriteU16(dst, osdConfig()->imu_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: @@ -1407,7 +1412,7 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF for (uint8_t index = 0; index < MAX_TEMP_SENSORS; ++index) { int16_t temperature; bool valid = getSensorTemperature(index, &temperature); - sbufWriteU16(dst, valid ? temperature : 0xFFFF); + sbufWriteU16(dst, valid ? temperature : -1000); } #endif break; @@ -2600,10 +2605,12 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src) osdConfigMutable()->alt_alarm = sbufReadU16(src); osdConfigMutable()->dist_alarm = sbufReadU16(src); osdConfigMutable()->neg_alt_alarm = sbufReadU16(src); - osdConfigMutable()->mpu_temp_alarm_min = sbufReadU16(src); - osdConfigMutable()->mpu_temp_alarm_max = sbufReadU16(src); + osdConfigMutable()->imu_temp_alarm_min = sbufReadU16(src); + osdConfigMutable()->imu_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; } @@ -2655,7 +2662,7 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src) case MSP2_INAV_SET_TEMP_SENSOR_CONFIG: #ifdef USE_TEMPERATURE_SENSOR - if (dataSize >= sizeof(tempSensorConfig_t) * MAX_TEMP_SENSORS) { + if (dataSize == sizeof(tempSensorConfig_t) * MAX_TEMP_SENSORS) { for (uint8_t index = 0; index < MAX_TEMP_SENSORS; ++index) { tempSensorConfig_t *sensorConfig = tempSensorConfigMutable(index); sensorConfig->type = sbufReadU8(src); diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index 0c9ffdd27ac..7b59e451e00 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -1592,12 +1592,22 @@ groups: field: neg_alt_alarm min: 0 max: 10000 - - name: osd_mpu_temp_alarm_min - field: mpu_temp_alarm_min + - name: osd_imu_temp_alarm_min + field: imu_temp_alarm_min min: -55 max: 125 - - name: osd_mpu_temp_alarm_max - field: mpu_temp_alarm_max + - name: osd_imu_temp_alarm_max + field: imu_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 diff --git a/src/main/io/osd.c b/src/main/io/osd.c index ce73e3e107d..b5140c2c346 100755 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -2294,11 +2294,11 @@ static bool osdDrawSingleElement(uint8_t item) break; } - case OSD_MPU_TEMPERATURE: + case OSD_IMU_TEMPERATURE: { int16_t temperature; - const bool valid = getMPUTemperature(&temperature); - osdDisplayTemperature(elemPosX, elemPosY, "MPU", valid, temperature, osdConfig()->mpu_temp_alarm_min, osdConfig()->mpu_temp_alarm_max); + const bool valid = getIMUTemperature(&temperature); + osdDisplayTemperature(elemPosX, elemPosY, "MPU", valid, temperature, osdConfig()->imu_temp_alarm_min, osdConfig()->imu_temp_alarm_max); return true; } @@ -2306,7 +2306,7 @@ static bool osdDrawSingleElement(uint8_t item) { int16_t temperature; const bool valid = getBaroTemperature(&temperature); - osdDisplayTemperature(elemPosX, elemPosY, "BARO", valid, temperature, osdConfig()->mpu_temp_alarm_min, osdConfig()->mpu_temp_alarm_max); + osdDisplayTemperature(elemPosX, elemPosY, "BARO", valid, temperature, osdConfig()->imu_temp_alarm_min, osdConfig()->imu_temp_alarm_max); return true; } @@ -2640,7 +2640,7 @@ void pgResetFn_osdConfig(osdConfig_t *osdConfig) osdConfig->item_pos[0][OSD_POWER] = OSD_POS(15, 1); - osdConfig->item_pos[0][OSD_MPU_TEMPERATURE] = OSD_POS(19, 2); + osdConfig->item_pos[0][OSD_IMU_TEMPERATURE] = OSD_POS(19, 2); osdConfig->item_pos[0][OSD_BARO_TEMPERATURE] = OSD_POS(19, 3); osdConfig->item_pos[0][OSD_TEMP_SENSOR_0_TEMPERATURE] = OSD_POS(19, 4); osdConfig->item_pos[0][OSD_TEMP_SENSOR_1_TEMPERATURE] = OSD_POS(19, 5); @@ -2669,10 +2669,12 @@ void pgResetFn_osdConfig(osdConfig_t *osdConfig) osdConfig->alt_alarm = 100; osdConfig->dist_alarm = 1000; osdConfig->neg_alt_alarm = 5; - osdConfig->mpu_temp_alarm_min = -200; - osdConfig->mpu_temp_alarm_max = 600; + osdConfig->imu_temp_alarm_min = -200; + osdConfig->imu_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; diff --git a/src/main/io/osd.h b/src/main/io/osd.h index 8adeabdc299..ecdf256bc85 100755 --- a/src/main/io/osd.h +++ b/src/main/io/osd.h @@ -122,7 +122,7 @@ typedef enum { OSD_MC_VEL_Z_PID_OUTPUTS, OSD_MC_POS_XYZ_P_OUTPUTS, OSD_3D_SPEED, - OSD_MPU_TEMPERATURE, + OSD_IMU_TEMPERATURE, OSD_BARO_TEMPERATURE, OSD_TEMP_SENSOR_0_TEMPERATURE, OSD_TEMP_SENSOR_1_TEMPERATURE, @@ -170,8 +170,8 @@ typedef struct osdConfig_s { uint16_t alt_alarm; // positive altitude in m uint16_t dist_alarm; // home distance in m uint16_t neg_alt_alarm; // abs(negative altitude) in m - int16_t mpu_temp_alarm_min; - int16_t mpu_temp_alarm_max; + int16_t imu_temp_alarm_min; + int16_t imu_temp_alarm_max; #ifdef USE_BARO int16_t baro_temp_alarm_min; int16_t baro_temp_alarm_max; diff --git a/src/main/rx/eleres.c b/src/main/rx/eleres.c index 8c826becbfb..2ebbe2077ba 100755 --- a/src/main/rx/eleres.c +++ b/src/main/rx/eleres.c @@ -272,8 +272,12 @@ static void telemetryRX(void) presfil -= presfil/4; presfil += baro.baroPressure; + + int16_t temperature; + const bool temp_valid = sensors(SENSOR_BARO) ? getBaroTemperature(&temperature) : getIMUTemperature(&temperature); + if (!temp_valid) temperature = -1250; // If temperature not valid report -125°C thempfil -= thempfil/8; - thempfil += DEGREES_TO_DECIDEGREES(getCurrentTemperature()); + thempfil += temperature; switch (telem_state++) { case 0: diff --git a/src/main/sensors/temperature.c b/src/main/sensors/temperature.c index 28373548fce..2d5ec965b42 100644 --- a/src/main/sensors/temperature.c +++ b/src/main/sensors/temperature.c @@ -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)]; @@ -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 @@ -133,8 +133,6 @@ void temperatureInit(void) } } -#endif - static bool temperatureSensorValueIsValid(uint8_t sensorIndex) { uint8_t mask = 1 << (sensorIndex % 8); @@ -142,6 +140,44 @@ static bool temperatureSensorValueIsValid(uint8_t sensorIndex) return sensorStatus[byteIndex] & mask; } +// returns decidegrees centigrade +bool getSensorTemperature(uint8_t sensorIndex, int16_t *temperature) +{ + *temperature = tempSensorValue[sensorIndex]; + return temperatureSensorValueIsValid(sensorIndex); +} + +// Converts 64bit integer address to hex format +// hex_address must be at least 17 bytes long (16 chars + NULL) +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]); + } +} + +// Converts address string in hex format to unsigned integer +// the hex_address parameter must be NULL or space terminated +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) { @@ -159,6 +195,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; @@ -178,14 +215,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; @@ -200,56 +237,27 @@ void temperatureUpdate(void) sensorStatus[byteIndex] &= ~statusMask; } +#endif #ifdef DS18B20_DRIVER_AVAILABLE ds18b20_start_conversion(); #endif } -bool getMPUTemperature(int16_t *temperature) +// returns decidegrees centigrade +bool getIMUTemperature(int16_t *temperature) { *temperature = mpuTemperature; return MPU_TEMP_VALID; } +// returns decidegrees centigrade bool getBaroTemperature(int16_t *temperature) { *temperature = baroTemperature; 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); diff --git a/src/main/sensors/temperature.h b/src/main/sensors/temperature.h index 069fd4e488e..14122b7e916 100644 --- a/src/main/sensors/temperature.h +++ b/src/main/sensors/temperature.h @@ -24,8 +24,6 @@ typedef enum { TEMP_SENSOR_NONE = 0, - TEMP_SENSOR_MPU, - TEMP_SENSOR_BARO, TEMP_SENSOR_LM75, TEMP_SENSOR_DS18B20 } tempSensorType_e; @@ -41,17 +39,17 @@ typedef struct { PG_DECLARE_ARRAY(tempSensorConfig_t, MAX_TEMP_SENSORS, tempSensorConfig); // Temperature is returned in degC*10 -bool getMPUTemperature(int16_t *temperature); +bool getIMUTemperature(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 diff --git a/src/main/telemetry/ibus_shared.c b/src/main/telemetry/ibus_shared.c index cf40e8f62fb..d81d4c758d7 100644 --- a/src/main/telemetry/ibus_shared.c +++ b/src/main/telemetry/ibus_shared.c @@ -141,19 +141,10 @@ static uint8_t dispatchMeasurementRequest(ibusAddress_t address) { } #endif if (SENSOR_ADDRESS_TYPE_LOOKUP[address].value == IBUS_MEAS_VALUE_TEMPERATURE) { //BARO_TEMP\GYRO_TEMP - /*if (sensors(SENSOR_BARO)) return sendIbusMeasurement2(address, (uint16_t) ((DEGREES_TO_CENTIDEGREES(getCurrentTemperature()) + 50) / 10 + IBUS_TEMPERATURE_OFFSET)); //int32_t*/ - if (sensors(SENSOR_BARO)) { - int16_t baroTemperature; - getBaroTemperature(&baroTemperature); - return sendIbusMeasurement2(address, (uint16_t) ((baroTemperature + 50) / 10 + IBUS_TEMPERATURE_OFFSET)); //int32_t // XXX - } else { - /* - * There is no temperature data - * assuming ((DEGREES_TO_CENTIDEGREES(getCurrentTemperature()) + 50) / 10 - * 0 degrees (no sensor) equals 50 / 10 = 5 - */ - return sendIbusMeasurement2(address, (uint16_t) (5 + IBUS_TEMPERATURE_OFFSET)); //int16_t - } + int16_t temperature; + const bool temp_valid = sensors(SENSOR_BARO) ? getBaroTemperature(&temperature) : getIMUTemperature(&temperature); + if (!temp_valid || (temperature < -50)) temperature = -50; // Minimum reported temperature is -5°C + return sendIbusMeasurement2(address, (uint16_t)((temperature + 50) / 10 + IBUS_TEMPERATURE_OFFSET)); } else if (SENSOR_ADDRESS_TYPE_LOOKUP[address].value == IBUS_MEAS_VALUE_RPM) { return sendIbusMeasurement2(address, (uint16_t) (rcCommand[THROTTLE])); } else if (SENSOR_ADDRESS_TYPE_LOOKUP[address].value == IBUS_MEAS_VALUE_EXTERNAL_VOLTAGE) { //VBAT