From 66733bace58466414e7db5aa7d2cc50f7d187eea Mon Sep 17 00:00:00 2001 From: Jacob Dahl Date: Mon, 23 Jan 2023 12:36:07 -0900 Subject: [PATCH] Added 3 new battery messages to support both smart batteries and power monitors. --- .../power/20010.BatteryContinuous.uavcan | 33 +++++++++++++++++++ .../power/20011.BatteryPeriodic.uavcan | 19 +++++++++++ .../equipment/power/20012.BatteryCells.uavcan | 8 +++++ 3 files changed, 60 insertions(+) create mode 100644 ardupilot/equipment/power/20010.BatteryContinuous.uavcan create mode 100644 ardupilot/equipment/power/20011.BatteryPeriodic.uavcan create mode 100644 ardupilot/equipment/power/20012.BatteryCells.uavcan diff --git a/ardupilot/equipment/power/20010.BatteryContinuous.uavcan b/ardupilot/equipment/power/20010.BatteryContinuous.uavcan new file mode 100644 index 0000000..2210014 --- /dev/null +++ b/ardupilot/equipment/power/20010.BatteryContinuous.uavcan @@ -0,0 +1,33 @@ +# +# Battery data to be sent continuously +# + +float16 temperature_cells # [C] : Pack mounted thermistor (preferably installed between cells), NAN: field not provided +float16 temperature_pcb # [C] : Battery PCB temperature (likely output FET(s) or current sense resistor), NAN: field not provided +float16 temperature_other # [C] : Application dependent, NAN: field not provided +float32 current # [A] : Positive: defined as a discharge current. Negative: defined as a charging current, NAN: field not provided +float32 voltage # [V] : Battery voltage +float16 state_of_charge # [%] : The estimated state of charge, in percent remaining (0 - 100). +uint8 slot_id # : The physical location of the battery on the aircraft. 0: field not provided +float32 capacity_consumed # [Ah] : This is either the consumption since power-on or since the battery was full, depending on the value of STATUS_FLAG_CAPACITY_RELATIVE_TO_FULL, NAN: field not provided +uint32 status_flags # : Fault, health, readiness, and other status indications + +uint32 STATUS_FLAG_READY_TO_USE = 1 +uint32 STATUS_FLAG_CHARGING = 2 +uint32 STATUS_FLAG_CELL_BALANCING = 4 +uint32 STATUS_FLAG_FAULT_CELL_IMBALANCE = 8 +uint32 STATUS_FLAG_AUTO_DISCHARGING = 16 +uint32 STATUS_FLAG_REQUIRES_SERVICE = 32 +uint32 STATUS_FLAG_BAD_BATTERY = 64 +uint32 STATUS_FLAG_PROTECTIONS_ENABLED = 128 +uint32 STATUS_FLAG_FAULT_PROTECTION_SYSTEM = 256 +uint32 STATUS_FLAG_FAULT_OVER_VOLT = 512 +uint32 STATUS_FLAG_FAULT_UNDER_VOLT = 1024 +uint32 STATUS_FLAG_FAULT_OVER_TEMP = 2048 +uint32 STATUS_FLAG_FAULT_UNDER_TEMP = 4096 +uint32 STATUS_FLAG_FAULT_OVER_CURRENT = 8192 +uint32 STATUS_FLAG_FAULT_SHORT_CIRCUIT = 16384 +uint32 STATUS_FLAG_FAULT_INCOMPATIBLE_VOLTAGE = 32768 +uint32 STATUS_FLAG_FAULT_INCOMPATIBLE_FIRMWARE = 65536 +uint32 STATUS_FLAG_FAULT_INCOMPATIBLE_CELLS_CONFIGURATION = 131072 +uint32 STATUS_FLAG_CAPACITY_RELATIVE_TO_FULL = 262144 diff --git a/ardupilot/equipment/power/20011.BatteryPeriodic.uavcan b/ardupilot/equipment/power/20011.BatteryPeriodic.uavcan new file mode 100644 index 0000000..410ce9d --- /dev/null +++ b/ardupilot/equipment/power/20011.BatteryPeriodic.uavcan @@ -0,0 +1,19 @@ +# +# Battery data to be sent statically upon request or periodically at a low rate +# Recommend that this message is sent at a maximum of 1Hz and nominally 0.2 Hz (IE: once every 5 seconds.) + +uint8[<=50] name # : Formatted as manufacturer_product, 0 terminated +uint8[<=32] serial_number # : Serial number in ASCII characters, 0 terminated +uint8[<=9] manufacture_date # : Manufacture date (DDMMYYYY) in ASCII characters, 0 terminated +float32 design_capacity # [Ah] : Fully charged design capacity. 0: field not provided. +uint8 cells_in_series # : Number of battery cells in series. 0: field not provided. +float16 nominal_voltage # [V] : Battery nominal voltage. Used for conversion between Wh and Ah. 0: field not provided. +float16 discharge_minimum_voltage # [V] : Minimum per-cell voltage when discharging. 0: field not provided. +float16 charging_minimum_voltage # [V] : Minimum per-cell voltage when charging. 0: field not provided. +float16 charging_maximum_voltage # [V] : Maximum per-cell voltage when charged. 0: field not provided. +float32 charging_maximum_current # [A] : Maximum pack continuous charge current. 0: field not provided. +float32 discharge_maximum_current # [A] : Maximum pack continuous discharge current. 0: field not provided. +float32 discharge_maximum_burst_current # [A] : Maximum pack discharge burst current for 30 seconds. 0: field not provided +float32 full_charge_capacity # [Ah] : Predicted battery capacity when fully charged (accounting for battery degradation), NAN: field not provided +uint16 cycle_count # : Lifetime count of the number of charge/discharge cycles (https://en.wikipedia.org/wiki/Charge_cycle). UINT16_MAX: field not provided. +uint8 state_of_health # [%] : State of Health (SOH) estimate, in percent (0 - 100). UINT8_MAX: field not provided. diff --git a/ardupilot/equipment/power/20012.BatteryCells.uavcan b/ardupilot/equipment/power/20012.BatteryCells.uavcan new file mode 100644 index 0000000..14a37b5 --- /dev/null +++ b/ardupilot/equipment/power/20012.BatteryCells.uavcan @@ -0,0 +1,8 @@ +# +# Battery cell voltages +# Rate: set by parameter on smart battery (default off) +# + +float16[<=24] voltages # [Volt] +uint16 index # Index of the first cell in the array, index 0 is cells at array indices 0 - 23, index 24 is cells at array indices 24 - 47, etc. +