AP_BattMonitor: fix comments re voltage scaling
This commit is contained in:
parent
912e089c18
commit
3e519b25a4
@ -72,6 +72,7 @@ public:
|
||||
return _singleton;
|
||||
}
|
||||
|
||||
// cell voltages in millivolts
|
||||
struct cells {
|
||||
uint16_t cells[AP_BATT_MONITOR_CELLS_MAX];
|
||||
};
|
||||
@ -109,7 +110,7 @@ public:
|
||||
bool healthy(uint8_t instance) const;
|
||||
bool healthy() const { return healthy(AP_BATT_PRIMARY_INSTANCE); }
|
||||
|
||||
/// voltage - returns battery voltage in millivolts
|
||||
/// voltage - returns battery voltage in volts
|
||||
float voltage(uint8_t instance) const;
|
||||
float voltage() const { return voltage(AP_BATT_PRIMARY_INSTANCE); }
|
||||
|
||||
@ -149,11 +150,11 @@ public:
|
||||
bool overpower_detected() const;
|
||||
bool overpower_detected(uint8_t instance) const;
|
||||
|
||||
// cell voltages
|
||||
// cell voltages in millivolts
|
||||
bool has_cell_voltages() { return has_cell_voltages(AP_BATT_PRIMARY_INSTANCE); }
|
||||
bool has_cell_voltages(const uint8_t instance) const;
|
||||
const cells & get_cell_voltages() const { return get_cell_voltages(AP_BATT_PRIMARY_INSTANCE); }
|
||||
const cells & get_cell_voltages(const uint8_t instance) const;
|
||||
const cells &get_cell_voltages() const { 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); }
|
||||
|
Loading…
Reference in New Issue
Block a user