Skip to content

Commit

Permalink
AP_BattMonitor: log external temperature if available
Browse files Browse the repository at this point in the history
  • Loading branch information
peterbarker authored and lthall committed Sep 3, 2023
1 parent 326541c commit dcc352c
Show file tree
Hide file tree
Showing 4 changed files with 26 additions and 11 deletions.
11 changes: 1 addition & 10 deletions libraries/AP_BattMonitor/AP_BattMonitor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -693,18 +693,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
Expand Down
15 changes: 15 additions & 0 deletions libraries/AP_BattMonitor/AP_BattMonitor_Backend.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -233,6 +233,21 @@ void AP_BattMonitor_Backend::check_failsafe_types(bool &low_voltage, bool &low_c
}
}

// 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
and consumed_mah based on the given percentage. Use percentage=100
Expand Down
3 changes: 3 additions & 0 deletions libraries/AP_BattMonitor/AP_BattMonitor_Backend.h
Original file line number Diff line number Diff line change
Expand Up @@ -48,6 +48,9 @@ class AP_BattMonitor_Backend
// 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;
Expand Down
8 changes: 7 additions & 1 deletion libraries/AP_BattMonitor/AP_BattMonitor_Logging.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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,
Expand All @@ -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,
};
Expand Down

0 comments on commit dcc352c

Please sign in to comment.