Compare commits

...

1 Commits

Author SHA1 Message Date
Matthias Grob e5e58ba290 Battery: minor refactor 2022-11-24 14:52:37 +01:00
3 changed files with 11 additions and 22 deletions
+5 -5
View File
@@ -12,10 +12,11 @@ float32 time_remaining_s # predicted time in seconds remaining until battery is
float32 temperature # temperature of the battery. NaN if unknown
uint8 cell_count # Number of cells, 0 if unknown
uint8 source # Battery source
uint8 BATTERY_SOURCE_POWER_MODULE = 0
uint8 BATTERY_SOURCE_EXTERNAL = 1
uint8 BATTERY_SOURCE_ESCS = 2
uint8 source # Battery source
uint8 priority # Zero based priority is the connection on the Power Controller V1..Vn AKA BrickN-1
uint16 capacity # actual capacity of the battery
uint16 cycle_count # number of discharge cycles the battery has experienced
@@ -33,7 +34,7 @@ float32 max_cell_voltage_delta # Max difference between individual cell voltages
bool is_powering_off # Power off event imminent indication, false if unknown
bool is_required # Set if the battery is explicitly required before arming
uint8 warning # Current battery warning
uint8 BATTERY_WARNING_NONE = 0 # no battery low voltage warning active
uint8 BATTERY_WARNING_LOW = 1 # warning of low voltage
uint8 BATTERY_WARNING_CRITICAL = 2 # critical voltage, return / abort immediately
@@ -42,6 +43,7 @@ uint8 BATTERY_WARNING_FAILED = 4 # the battery has failed completely
uint8 BATTERY_STATE_UNHEALTHY = 6 # Battery is diagnosed to be defective or an error occurred, usage is discouraged / prohibited. Possible causes (faults) are listed in faults field.
uint8 BATTERY_STATE_CHARGING = 7 # Battery is charging
uint16 faults # Smart battery supply status/fault flags (bitmask) for health indication
uint8 BATTERY_FAULT_DEEP_DISCHARGE = 0 # Battery has deep discharged
uint8 BATTERY_FAULT_SPIKES = 1 # Voltage spikes
uint8 BATTERY_FAULT_CELL_FAIL= 2 # One or more cells have failed
@@ -55,11 +57,9 @@ uint8 BATTERY_FAULT_HARDWARE_FAILURE = 9 # hardware problem
uint8 BATTERY_WARNING_OVER_TEMPERATURE = 10 # Over-temperature
uint8 BATTERY_FAULT_COUNT = 11 # Counter - keep it as last element!
uint16 faults # Smart battery supply status/fault flags (bitmask) for health indication.
uint32 custom_faults # Bitmask indicating smart battery internal manufacturer faults, those are not user actionable.
uint8 warning # Current battery warning
uint8 mode # Battery mode. Note, the normal operation mode
uint8 mode # Battery mode. Note, the normal operation mode
uint8 BATTERY_MODE_UNKNOWN = 0 # Battery does not support a mode, or if it does, is operational
uint8 BATTERY_MODE_AUTO_DISCHARGING = 1 # Battery is auto discharging (towards storage level)
uint8 BATTERY_MODE_HOT_SWAP = 2 # Battery in hot-swap mode
+1 -11
View File
@@ -97,12 +97,10 @@ UavcanBatteryBridge::battery_sub_cb(const uavcan::ReceivedDataStructure<uavcan::
}
if (_batt_update_mod[instance] == BatteryDataType::Filter) {
filterData(msg, instance);
return;
}
_battery_status[instance].timestamp = hrt_absolute_time();
_battery_status[instance].voltage_v = msg.voltage;
_battery_status[instance].voltage_filtered_v = msg.voltage;
_battery_status[instance].current_a = msg.current;
@@ -115,18 +113,13 @@ UavcanBatteryBridge::battery_sub_cb(const uavcan::ReceivedDataStructure<uavcan::
}
_battery_status[instance].remaining = msg.state_of_charge_pct / 100.0f; // between 0 and 1
// _battery_status[instance].scale = msg.; // Power scaling factor, >= 1, or -1 if unknown
_battery_status[instance].temperature = msg.temperature + CONSTANTS_ABSOLUTE_NULL_CELSIUS; // Kelvin to Celsius
// _battery_status[instance].cell_count = msg.;
_battery_status[instance].connected = true;
_battery_status[instance].source = msg.status_flags & uavcan::equipment::power::BatteryInfo::STATUS_FLAG_IN_USE;
// _battery_status[instance].priority = msg.;
_battery_status[instance].capacity = msg.full_charge_capacity_wh;
_battery_status[instance].full_charge_capacity_wh = msg.full_charge_capacity_wh;
_battery_status[instance].remaining_capacity_wh = msg.remaining_capacity_wh;
// _battery_status[instance].cycle_count = msg.;
_battery_status[instance].time_remaining_s = NAN;
// _battery_status[instance].average_time_to_empty = msg.;
_battery_status[instance].serial_number = msg.model_instance_id;
_battery_status[instance].id = msg.getSrcNodeID().get();
@@ -138,12 +131,9 @@ UavcanBatteryBridge::battery_sub_cb(const uavcan::ReceivedDataStructure<uavcan::
_battery_status[instance].cell_count = 1;
}
// _battery_status[instance].max_cell_voltage_delta = msg.;
// _battery_status[instance].is_powering_off = msg.;
determineWarning(_battery_status[instance].remaining);
_battery_status[instance].warning = _warning;
_battery_status[instance].timestamp = hrt_absolute_time();
if (_batt_update_mod[instance] == BatteryDataType::Raw) {
publish(msg.getSrcNodeID().get(), &_battery_status[instance]);
+5 -6
View File
@@ -107,10 +107,9 @@ private:
static_assert(battery_status_s::MAX_INSTANCES <= BATTERY_INDEX_4, "Battery array too big");
Battery battery1 = {BATTERY_INDEX_1, this, SAMPLE_INTERVAL_US, battery_status_s::BATTERY_SOURCE_EXTERNAL};
Battery battery2 = {BATTERY_INDEX_2, this, SAMPLE_INTERVAL_US, battery_status_s::BATTERY_SOURCE_EXTERNAL};
Battery battery3 = {BATTERY_INDEX_3, this, SAMPLE_INTERVAL_US, battery_status_s::BATTERY_SOURCE_EXTERNAL};
Battery battery4 = {BATTERY_INDEX_4, this, SAMPLE_INTERVAL_US, battery_status_s::BATTERY_SOURCE_EXTERNAL};
Battery *_battery[battery_status_s::MAX_INSTANCES] = { &battery1, &battery2, &battery3, &battery4 };
Battery battery1{BATTERY_INDEX_1, this, SAMPLE_INTERVAL_US, battery_status_s::BATTERY_SOURCE_EXTERNAL};
Battery battery2{BATTERY_INDEX_2, this, SAMPLE_INTERVAL_US, battery_status_s::BATTERY_SOURCE_EXTERNAL};
Battery battery3{BATTERY_INDEX_3, this, SAMPLE_INTERVAL_US, battery_status_s::BATTERY_SOURCE_EXTERNAL};
Battery battery4{BATTERY_INDEX_4, this, SAMPLE_INTERVAL_US, battery_status_s::BATTERY_SOURCE_EXTERNAL};
Battery *_battery[battery_status_s::MAX_INSTANCES] {&battery1, &battery2, &battery3, &battery4};
};