AP_BattMonitor: add set_temperature() by external temperature sources/libraries

This commit is contained in:
Tom Pittenger 2022-10-12 11:02:19 -07:00 committed by Andrew Tridgell
parent 89bcd65603
commit 812128125b
2 changed files with 41 additions and 0 deletions

View File

@ -644,11 +644,43 @@ bool AP_BattMonitor::get_temperature(float &temperature, const uint8_t instance)
return false;
}
#if AP_TEMPERATURE_SENSOR_ENABLED
if (state[instance].temperature_external_use) {
temperature = state[instance].temperature_external;
return true;
}
#endif
temperature = state[instance].temperature;
return drivers[instance]->has_temperature();
}
#if AP_TEMPERATURE_SENSOR_ENABLED
// return true when successfully setting a battery temperature from an external source by instance
bool AP_BattMonitor::set_temperature(const float temperature, const uint8_t instance)
{
if (instance >= AP_BATT_MONITOR_MAX_INSTANCES || drivers[instance] == nullptr) {
return false;
}
state[instance].temperature_external = temperature;
state[instance].temperature_external_use = true;
return true;
}
// return true when successfully setting a battery temperature from an external source by serial_number
bool AP_BattMonitor::set_temperature_by_serial_number(const float temperature, const int32_t serial_number)
{
bool success = false;
for (uint8_t i = 0; i < _num_instances; i++) {
if (drivers[i] != nullptr && get_serial_number(i) == serial_number) {
success |= set_temperature(temperature, i);
}
}
return success;
}
#endif // AP_TEMPERATURE_SENSOR_ENABLED
// return true if cycle count can be provided and fills in cycles argument
bool AP_BattMonitor::get_cycle_count(uint8_t instance, uint16_t &cycles) const
{

View File

@ -3,6 +3,7 @@
#include <AP_Common/AP_Common.h>
#include <AP_Param/AP_Param.h>
#include <AP_Math/AP_Math.h>
#include <AP_TemperatureSensor/AP_TemperatureSensor_config.h>
#include <GCS_MAVLink/GCS_MAVLink.h>
#include "AP_BattMonitor_Params.h"
@ -141,6 +142,10 @@ public:
uint32_t low_voltage_start_ms; // time when voltage dropped below the minimum in milliseconds
uint32_t critical_voltage_start_ms; // critical voltage failsafe start timer in milliseconds
float temperature; // battery temperature in degrees Celsius
#if AP_TEMPERATURE_SENSOR_ENABLED
bool temperature_external_use;
float temperature_external; // battery temperature set by an external source in degrees Celsius
#endif
uint32_t temperature_time; // timestamp of the last received temperature message
float voltage_resting_estimate; // voltage with sag removed based on current and resistance estimate in Volt
float resistance; // resistance, in Ohms, calculated by comparing resting voltage vs in flight voltage
@ -234,6 +239,10 @@ public:
// temperature
bool get_temperature(float &temperature) const { return get_temperature(temperature, AP_BATT_PRIMARY_INSTANCE); }
bool get_temperature(float &temperature, const uint8_t instance) const;
#if AP_TEMPERATURE_SENSOR_ENABLED
bool set_temperature(const float temperature, const uint8_t instance);
bool set_temperature_by_serial_number(const float temperature, const int32_t serial_number);
#endif
// cycle count
bool get_cycle_count(uint8_t instance, uint16_t &cycles) const;