From 7e0c178c6cbd18da3ceee9ff615dc3203a1ec708 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Mon, 4 Sep 2023 11:59:43 +1000 Subject: [PATCH] SITL: add temperature to battery simulation --- libraries/SITL/SIM_Aircraft.h | 1 + libraries/SITL/SIM_Battery.cpp | 9 +++++++++ libraries/SITL/SIM_Battery.h | 8 ++++++++ 3 files changed, 18 insertions(+) diff --git a/libraries/SITL/SIM_Aircraft.h b/libraries/SITL/SIM_Aircraft.h index 0a4d576893..645f78c7fc 100644 --- a/libraries/SITL/SIM_Aircraft.h +++ b/libraries/SITL/SIM_Aircraft.h @@ -151,6 +151,7 @@ public: void set_dronecan_device(DroneCANDevice *_dronecan) { dronecan = _dronecan; } #endif float get_battery_voltage() const { return battery_voltage; } + float get_battery_temperature() const { return battery.get_temperature(); } protected: SIM *sitl; diff --git a/libraries/SITL/SIM_Battery.cpp b/libraries/SITL/SIM_Battery.cpp index ba8a17b263..d5a7219c36 100644 --- a/libraries/SITL/SIM_Battery.cpp +++ b/libraries/SITL/SIM_Battery.cpp @@ -150,6 +150,15 @@ void Battery::set_current(float current) } voltage_filter.apply(voltage); + + { + const uint64_t temperature_dt = now - temperature.last_update_micros; + temperature.last_update_micros = now; + // 1 amp*1 second == 0.1 degrees of energy. Did those units hurt? + temperature.kelvin += 0.1 * current * temperature_dt * 0.000001; + // decay temperature at some %second towards ambient + temperature.kelvin -= (temperature.kelvin - 273) * 0.10 * temperature_dt * 0.000001; + } } float Battery::get_voltage(void) const diff --git a/libraries/SITL/SIM_Battery.h b/libraries/SITL/SIM_Battery.h index 14c72d08df..af592c00eb 100644 --- a/libraries/SITL/SIM_Battery.h +++ b/libraries/SITL/SIM_Battery.h @@ -34,6 +34,9 @@ public: void set_current(float current_amps); float get_voltage(void) const; + // return battery temperature in Kelvin: + float get_temperature(void) const { return temperature.kelvin; } + private: float capacity_Ah; float resistance; @@ -42,6 +45,11 @@ private: float remaining_Ah; uint64_t last_us; + struct { + float kelvin = 273; + uint64_t last_update_micros; + } temperature; + // 10Hz filter for battery voltage LowPassFilterFloat voltage_filter{10};