SITL: add temperature to battery simulation

This commit is contained in:
Peter Barker 2023-09-04 11:59:43 +10:00 committed by Peter Barker
parent ef3d42ee9d
commit 7e0c178c6c
3 changed files with 18 additions and 0 deletions

View File

@ -151,6 +151,7 @@ public:
void set_dronecan_device(DroneCANDevice *_dronecan) { dronecan = _dronecan; } void set_dronecan_device(DroneCANDevice *_dronecan) { dronecan = _dronecan; }
#endif #endif
float get_battery_voltage() const { return battery_voltage; } float get_battery_voltage() const { return battery_voltage; }
float get_battery_temperature() const { return battery.get_temperature(); }
protected: protected:
SIM *sitl; SIM *sitl;

View File

@ -150,6 +150,15 @@ void Battery::set_current(float current)
} }
voltage_filter.apply(voltage); 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 float Battery::get_voltage(void) const

View File

@ -34,6 +34,9 @@ public:
void set_current(float current_amps); void set_current(float current_amps);
float get_voltage(void) const; float get_voltage(void) const;
// return battery temperature in Kelvin:
float get_temperature(void) const { return temperature.kelvin; }
private: private:
float capacity_Ah; float capacity_Ah;
float resistance; float resistance;
@ -42,6 +45,11 @@ private:
float remaining_Ah; float remaining_Ah;
uint64_t last_us; uint64_t last_us;
struct {
float kelvin = 273;
uint64_t last_update_micros;
} temperature;
// 10Hz filter for battery voltage // 10Hz filter for battery voltage
LowPassFilterFloat voltage_filter{10}; LowPassFilterFloat voltage_filter{10};