AP_ESC_Telem: allow external libraries, like AP_TemperatureSensor, to override the temperature

This commit is contained in:
Tom Pittenger 2022-10-11 12:34:32 -07:00 committed by Andrew Tridgell
parent 475fb67c2b
commit 89bcd65603
3 changed files with 26 additions and 1 deletions

View File

@ -419,12 +419,29 @@ void AP_ESC_Telem::update_telem_data(const uint8_t esc_index, const AP_ESC_Telem
_have_data = true;
#if AP_TEMPERATURE_SENSOR_ENABLED
// if it's ever been set externally ignore normal "internal" updates
if (data_mask & AP_ESC_Telem_Backend::TelemetryType::TEMPERATURE_EXTERNAL) {
_temperature_is_external[esc_index] = true;
_telem_data[esc_index].temperature_cdeg = new_data.temperature_cdeg;
} else if ((data_mask & AP_ESC_Telem_Backend::TelemetryType::TEMPERATURE) && !_temperature_is_external[esc_index]) {
_telem_data[esc_index].temperature_cdeg = new_data.temperature_cdeg;
}
if (data_mask & AP_ESC_Telem_Backend::TelemetryType::MOTOR_TEMPERATURE_EXTERNAL) {
_motor_temp_is_external[esc_index] = true;
_telem_data[esc_index].motor_temp_cdeg = new_data.motor_temp_cdeg;
} else if ((data_mask & AP_ESC_Telem_Backend::TelemetryType::MOTOR_TEMPERATURE) && !_motor_temp_is_external[esc_index]) {
_telem_data[esc_index].motor_temp_cdeg = new_data.motor_temp_cdeg;
}
#else
if (data_mask & AP_ESC_Telem_Backend::TelemetryType::TEMPERATURE) {
_telem_data[esc_index].temperature_cdeg = new_data.temperature_cdeg;
}
if (data_mask & AP_ESC_Telem_Backend::TelemetryType::MOTOR_TEMPERATURE) {
_telem_data[esc_index].motor_temp_cdeg = new_data.motor_temp_cdeg;
}
#endif
if (data_mask & AP_ESC_Telem_Backend::TelemetryType::VOLTAGE) {
_telem_data[esc_index].voltage = new_data.voltage;
}

View File

@ -2,6 +2,7 @@
#include <AP_HAL/AP_HAL.h>
#include <AP_Param/AP_Param.h>
#include <AP_TemperatureSensor/AP_TemperatureSensor_config.h>
#include "AP_ESC_Telem_Backend.h"
#if HAL_WITH_ESC_TELEM
@ -118,6 +119,11 @@ private:
// telemetry data
volatile AP_ESC_Telem_Backend::TelemetryData _telem_data[ESC_TELEM_MAX_ESCS];
#if AP_TEMPERATURE_SENSOR_ENABLED
bool _temperature_is_external[ESC_TELEM_MAX_ESCS];
bool _motor_temp_is_external[ESC_TELEM_MAX_ESCS];
#endif
uint32_t _last_telem_log_ms[ESC_TELEM_MAX_ESCS];
uint32_t _last_rpm_log_us[ESC_TELEM_MAX_ESCS];
uint8_t next_idx;

View File

@ -41,7 +41,9 @@ public:
VOLTAGE = 1 << 2,
CURRENT = 1 << 3,
CONSUMPTION = 1 << 4,
USAGE = 1 << 5
USAGE = 1 << 5,
TEMPERATURE_EXTERNAL = 1 << 6,
MOTOR_TEMPERATURE_EXTERNAL = 1 << 7,
};