mirror of https://github.com/ArduPilot/ardupilot
AP_BattMonitor: log external temperature if available
This commit is contained in:
parent
f87c138393
commit
7aea21bd40
|
@ -879,18 +879,9 @@ bool AP_BattMonitor::get_temperature(float &temperature, const uint8_t instance)
|
|||
{
|
||||
if (instance >= _num_instances || drivers[instance] == nullptr) {
|
||||
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();
|
||||
return drivers[instance]->get_temperature(temperature);
|
||||
}
|
||||
|
||||
#if AP_TEMPERATURE_SENSOR_ENABLED
|
||||
|
|
|
@ -272,6 +272,20 @@ void AP_BattMonitor_Backend::update_esc_telem_outbound()
|
|||
}
|
||||
#endif
|
||||
|
||||
// returns true if battery monitor provides temperature
|
||||
bool AP_BattMonitor_Backend::get_temperature(float &temperature) const
|
||||
{
|
||||
#if AP_TEMPERATURE_SENSOR_ENABLED
|
||||
if (_state.temperature_external_use) {
|
||||
temperature = _state.temperature_external;
|
||||
return true;
|
||||
}
|
||||
#endif
|
||||
|
||||
temperature = _state.temperature;
|
||||
|
||||
return has_temperature();
|
||||
}
|
||||
|
||||
/*
|
||||
default implementation for reset_remaining(). This sets consumed_wh
|
||||
|
|
|
@ -48,6 +48,9 @@ public:
|
|||
// returns true if battery monitor provides temperature
|
||||
virtual bool has_temperature() const { return false; }
|
||||
|
||||
// returns true if temperature retrieved successfully
|
||||
virtual bool get_temperature(float &temperature) const;
|
||||
|
||||
// capacity_remaining_pct - returns true if the battery % is available and writes to the percentage argument
|
||||
// returns false if the battery is unhealthy, does not have current monitoring, or the pack_capacity is too small
|
||||
virtual bool capacity_remaining_pct(uint8_t &percentage) const WARN_IF_UNUSED;
|
||||
|
|
|
@ -10,6 +10,12 @@ void AP_BattMonitor_Backend::Log_Write_BAT(const uint8_t instance, const uint64_
|
|||
uint8_t percent = -1;
|
||||
IGNORE_RETURN(capacity_remaining_pct(percent));
|
||||
|
||||
float temperature;
|
||||
int16_t temperature_cd = 0;
|
||||
if (get_temperature(temperature)) {
|
||||
temperature_cd = temperature * 100.0;
|
||||
}
|
||||
|
||||
const struct log_BAT pkt{
|
||||
LOG_PACKET_HEADER_INIT(LOG_BAT_MSG),
|
||||
time_us : time_us,
|
||||
|
@ -19,7 +25,7 @@ void AP_BattMonitor_Backend::Log_Write_BAT(const uint8_t instance, const uint64_
|
|||
current_amps : has_curr ? _state.current_amps : AP::logger().quiet_nanf(),
|
||||
current_total : has_curr ? _state.consumed_mah : AP::logger().quiet_nanf(),
|
||||
consumed_wh : has_curr ? _state.consumed_wh : AP::logger().quiet_nanf(),
|
||||
temperature : (int16_t) ( has_temperature() ? _state.temperature * 100 : 0),
|
||||
temperature : temperature_cd,
|
||||
resistance : _state.resistance,
|
||||
rem_percent : percent,
|
||||
health : _state.healthy
|
||||
|
|
Loading…
Reference in New Issue