AP_BattMonitor: Add temperature interface

This commit is contained in:
Michael du Breuil 2017-04-08 01:20:08 -07:00 committed by Francisco Ferreira
parent e39ae6d48c
commit 121ebebfef
2 changed files with 19 additions and 0 deletions

View File

@ -346,3 +346,14 @@ const AP_BattMonitor::cells & AP_BattMonitor::get_cell_voltages(const uint8_t in
return state[instance].cell_voltages;
}
}
// returns true if there is a temperature reading
bool AP_BattMonitor::get_temperature(float &temperature, const uint8_t instance) const
{
if (instance >= AP_BATT_MONITOR_MAX_INSTANCES) {
return false;
} else {
temperature = state[instance].temperature;
return (AP_HAL::millis() - state[instance].temperature_time) <= AP_BATT_MONITOR_TIMEOUT;
}
}

View File

@ -15,6 +15,8 @@
#define AP_BATT_LOW_VOLT_TIMEOUT_MS 10000 // low voltage of 10 seconds will cause battery_exhausted to return true
#define AP_BATT_MAX_WATT_DEFAULT 0
#define AP_BATT_MONITOR_TIMEOUT 5000
// declare backend class
class AP_BattMonitor_Backend;
class AP_BattMonitor_Analog;
@ -60,6 +62,8 @@ public:
uint32_t last_time_micros; // time when voltage and current was last read
uint32_t low_voltage_start_ms; // time when voltage dropped below the minimum
cells cell_voltages; // battery cell voltages in millivolts, 10 cells matches the MAVLink spec
float temperature; // battery temperature in celsius
uint32_t temperature_time; // timestamp of the last recieved temperature message
};
// Return the number of battery monitor instances
@ -126,6 +130,10 @@ public:
const cells & get_cell_voltages() { return get_cell_voltages(AP_BATT_PRIMARY_INSTANCE); };
const cells & get_cell_voltages(const uint8_t instance) const;
// 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;
static const struct AP_Param::GroupInfo var_info[];
protected: