From d790962a88e84c133b5e38cc336711aacaf7b8f6 Mon Sep 17 00:00:00 2001 From: Hamish Willee Date: Thu, 1 May 2025 13:13:16 +1000 Subject: [PATCH 01/12] BatteryStatus.msg - docs update --- msg/versioned/BatteryStatus.msg | 125 ++++++++++++++++---------------- 1 file changed, 64 insertions(+), 61 deletions(-) diff --git a/msg/versioned/BatteryStatus.msg b/msg/versioned/BatteryStatus.msg index 852db501dfd6..834dc324fced 100644 --- a/msg/versioned/BatteryStatus.msg +++ b/msg/versioned/BatteryStatus.msg @@ -1,74 +1,77 @@ +# Battery status + uint32 MESSAGE_VERSION = 0 -uint64 timestamp # time since system start (microseconds) -bool connected # Whether or not a battery is connected, based on a voltage threshold -float32 voltage_v # Battery voltage in volts, 0 if unknown -float32 current_a # Battery current in amperes, -1 if unknown -float32 current_average_a # Battery current average in amperes (for FW average in level flight), -1 if unknown -float32 discharged_mah # Discharged amount in mAh, -1 if unknown -float32 remaining # From 1 to 0, -1 if unknown -float32 scale # Power scaling factor, >= 1, or -1 if unknown -float32 time_remaining_s # predicted time in seconds remaining until battery is empty under previous averaged load, NAN if unknown -float32 temperature # Temperature of the battery in degrees Celcius, NaN if unknown -uint8 cell_count # Number of cells, 0 if unknown +uint64 timestamp # Time since system start [us] +bool connected # Whether or not a battery is connected, based on a voltage threshold +float32 voltage_v # Battery voltage [V] [@invalid 0] +float32 current_a # Battery current [A] [@invalid -1] +float32 current_average_a # Battery current average (for FW average in level flight) [A] [@invalid -1] +float32 discharged_mah # Discharged amount [mAh] [@invalid -1] +float32 remaining # Remaining capacity [@range 0,1] [@invalid -1] +float32 scale # Power scaling factor [@range 1,] [@invalid -1] +float32 time_remaining_s # Predicted time remaining until battery is empty under previous averaged load [s] [@invalid NaN] +float32 temperature # Temperature of the battery [°C] [@invalid NaN] +uint8 cell_count # Number of cells [@invalid 0] + -uint8 SOURCE_POWER_MODULE = 0 -uint8 SOURCE_EXTERNAL = 1 -uint8 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 -uint16 average_time_to_empty # predicted remaining battery capacity based on the average rate of discharge in min -uint16 serial_number # serial number of the battery pack -uint16 manufacture_date # manufacture date, part of serial number of the battery pack. Formatted as: Day + Month×32 + (Year–1980)×512 -uint16 state_of_health # state of health. FullChargeCapacity/DesignCapacity, 0-100%. -uint16 max_error # max error, expected margin of error in % in the state-of-charge calculation with a range of 1 to 100% -uint8 id # ID number of a battery. Should be unique and consistent for the lifetime of a vehicle. 1-indexed. -uint16 interface_error # interface error counter +uint8 source # Battery source [@enum SOURCE] +uint8 SOURCE_POWER_MODULE = 0 # Power module +uint8 SOURCE_EXTERNAL = 1 # External +uint8 SOURCE_ESCS = 2 # ESCs -float32[14] voltage_cell_v # Battery individual cell voltages, 0 if unknown -float32 max_cell_voltage_delta # Max difference between individual cell voltages +uint8 priority # Zero based priority is the connection on the Power Controller V1..Vn AKA BrickN-1 +uint16 capacity # Actual capacity of the battery [Ah] +uint16 cycle_count # Number of discharge cycles the battery has experienced +uint16 average_time_to_empty # Predicted remaining battery capacity based on the average rate of discharge [minutes] +uint16 serial_number # Serial number of the battery pack +uint16 manufacture_date # Manufacture date, part of serial number of the battery pack. Formatted as: Day + Month×32 + (Year–1980)×512 +uint16 state_of_health # State of health. FullChargeCapacity/DesignCapacity [%] [@range 0, 100]. +uint16 max_error # Max error, expected margin of error in % in the state-of-charge calculation with a range of 1 to 100% +uint8 id # ID number of a battery. Should be unique and consistent for the lifetime of a vehicle. 1-indexed. +uint16 interface_error # Interface error counter -bool is_powering_off # Power off event imminent indication, false if unknown -bool is_required # Set if the battery is explicitly required before arming +float32[14] voltage_cell_v # Battery individual cell voltages, 0 if unknown +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_NONE = 0 # no battery low voltage warning active -uint8 WARNING_LOW = 1 # warning of low voltage -uint8 WARNING_CRITICAL = 2 # critical voltage, return / abort immediately -uint8 WARNING_EMERGENCY = 3 # immediate landing required -uint8 WARNING_FAILED = 4 # the battery has failed completely -uint8 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 STATE_CHARGING = 7 # Battery is charging +uint8 warning # Current battery warning [@enum WARNING] +uint8 WARNING_NONE = 0 # No battery low voltage warning active +uint8 WARNING_LOW = 1 # Low voltage warning +uint8 WARNING_CRITICAL = 2 # Critical voltage, return / abort immediately +uint8 WARNING_EMERGENCY = 3 # Immediate landing required +uint8 WARNING_FAILED = 4 # Battery has failed completely -uint8 FAULT_DEEP_DISCHARGE = 0 # Battery has deep discharged -uint8 FAULT_SPIKES = 1 # Voltage spikes -uint8 FAULT_CELL_FAIL= 2 # One or more cells have failed -uint8 FAULT_OVER_CURRENT = 3 # Over-current -uint8 FAULT_OVER_TEMPERATURE = 4 # Over-temperature -uint8 FAULT_UNDER_TEMPERATURE = 5 # Under-temperature fault -uint8 FAULT_INCOMPATIBLE_VOLTAGE = 6 # Vehicle voltage is not compatible with this battery (batteries on same power rail should have similar voltage). -uint8 FAULT_INCOMPATIBLE_FIRMWARE = 7 # Battery firmware is not compatible with current autopilot firmware -uint8 FAULT_INCOMPATIBLE_MODEL = 8 # Battery model is not supported by the system -uint8 FAULT_HARDWARE_FAILURE = 9 # hardware problem -uint8 FAULT_FAILED_TO_ARM = 10 # Battery had a problem while arming -uint8 FAULT_COUNT = 11 # Counter - keep it as last element! +uint8 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 STATE_CHARGING = 7 # Battery is charging -uint16 faults # Smart battery supply status/fault flags (bitmask) for health indication. -uint8 warning # Current battery warning +uint16 faults # Smart battery supply status/fault flags (bitmask) for health indication. [@enum FAULT] +uint8 FAULT_DEEP_DISCHARGE = 0 # Battery has deep discharged +uint8 FAULT_SPIKES = 1 # Voltage spikes +uint8 FAULT_CELL_FAIL= 2 # One or more cells have failed +uint8 FAULT_OVER_CURRENT = 3 # Over-current +uint8 FAULT_OVER_TEMPERATURE = 4 # Over-temperature +uint8 FAULT_UNDER_TEMPERATURE = 5 # Under-temperature fault +uint8 FAULT_INCOMPATIBLE_VOLTAGE = 6 # Vehicle voltage is not compatible with this battery (batteries on same power rail should have similar voltage). +uint8 FAULT_INCOMPATIBLE_FIRMWARE = 7 # Battery firmware is not compatible with current autopilot firmware +uint8 FAULT_INCOMPATIBLE_MODEL = 8 # Battery model is not supported by the system +uint8 FAULT_HARDWARE_FAILURE = 9 # hardware problem +uint8 FAULT_FAILED_TO_ARM = 10 # Battery had a problem while arming +uint8 FAULT_COUNT = 11 # Counter - keep it as last element! uint8 MAX_INSTANCES = 4 -float32 full_charge_capacity_wh # The compensated battery capacity -float32 remaining_capacity_wh # The compensated battery capacity remaining -uint16 over_discharge_count # Number of battery overdischarge -float32 nominal_voltage # Nominal voltage of the battery pack +float32 full_charge_capacity_wh # The compensated battery capacity [Wh] +float32 remaining_capacity_wh # The compensated battery capacity remaining [Wh] +uint16 over_discharge_count # Number of battery overdischarge +float32 nominal_voltage # Nominal voltage of the battery pack [V] -float32 internal_resistance_estimate # [Ohm] Internal resistance per cell estimate -float32 ocv_estimate # [V] Open circuit voltage estimate -float32 ocv_estimate_filtered # [V] Filtered open circuit voltage estimate -float32 volt_based_soc_estimate # [0, 1] Normalized volt based state of charge estimate -float32 voltage_prediction # [V] Predicted voltage -float32 prediction_error # [V] Prediction error -float32 estimation_covariance_norm # Norm of the covariance matrix +float32 internal_resistance_estimate # Internal resistance per cell estimate [Ohm] +float32 ocv_estimate # Open circuit voltage estimate [V] +float32 ocv_estimate_filtered # Filtered open circuit voltage estimate [V] +float32 volt_based_soc_estimate # Normalized volt based state of charge estimate [@range 0, 1] +float32 voltage_prediction # Predicted voltage [V] +float32 prediction_error # Prediction error [V] +float32 estimation_covariance_norm # Norm of the covariance matrix From d4c77197fa7a7210f108daad5b150b66b05420db Mon Sep 17 00:00:00 2001 From: Hamish Willee Date: Thu, 1 May 2025 13:22:54 +1000 Subject: [PATCH 02/12] Update msg/versioned/BatteryStatus.msg --- msg/versioned/BatteryStatus.msg | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/msg/versioned/BatteryStatus.msg b/msg/versioned/BatteryStatus.msg index 834dc324fced..517f524cf4ec 100644 --- a/msg/versioned/BatteryStatus.msg +++ b/msg/versioned/BatteryStatus.msg @@ -27,7 +27,7 @@ uint16 average_time_to_empty # Predicted remaining battery capacity based on the uint16 serial_number # Serial number of the battery pack uint16 manufacture_date # Manufacture date, part of serial number of the battery pack. Formatted as: Day + Month×32 + (Year–1980)×512 uint16 state_of_health # State of health. FullChargeCapacity/DesignCapacity [%] [@range 0, 100]. -uint16 max_error # Max error, expected margin of error in % in the state-of-charge calculation with a range of 1 to 100% +uint16 max_error # Max error, expected margin of error in the state-of-charge calculation [%] [@range 1, 100] uint8 id # ID number of a battery. Should be unique and consistent for the lifetime of a vehicle. 1-indexed. uint16 interface_error # Interface error counter From 097796039cb0446834ac07441adfe848e3e3fc73 Mon Sep 17 00:00:00 2001 From: Hamish Willee Date: Thu, 1 May 2025 13:24:22 +1000 Subject: [PATCH 03/12] Update msg/versioned/BatteryStatus.msg --- msg/versioned/BatteryStatus.msg | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/msg/versioned/BatteryStatus.msg b/msg/versioned/BatteryStatus.msg index 517f524cf4ec..d5ab2dd53896 100644 --- a/msg/versioned/BatteryStatus.msg +++ b/msg/versioned/BatteryStatus.msg @@ -31,7 +31,7 @@ uint16 max_error # Max error, expected margin of error in the state-of-charge ca uint8 id # ID number of a battery. Should be unique and consistent for the lifetime of a vehicle. 1-indexed. uint16 interface_error # Interface error counter -float32[14] voltage_cell_v # Battery individual cell voltages, 0 if unknown +float32[14] voltage_cell_v # Battery individual cell voltages [V] [@invalid 0] float32 max_cell_voltage_delta # Max difference between individual cell voltages bool is_powering_off # Power off event imminent indication, false if unknown From 6d028be2db0b467674b247bc8c1bf1967cb03259 Mon Sep 17 00:00:00 2001 From: Hamish Willee Date: Thu, 8 May 2025 12:25:13 +1000 Subject: [PATCH 04/12] Update msg/versioned/BatteryStatus.msg --- msg/versioned/BatteryStatus.msg | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/msg/versioned/BatteryStatus.msg b/msg/versioned/BatteryStatus.msg index d5ab2dd53896..cd4ca0158f2a 100644 --- a/msg/versioned/BatteryStatus.msg +++ b/msg/versioned/BatteryStatus.msg @@ -21,7 +21,7 @@ uint8 SOURCE_EXTERNAL = 1 # External uint8 SOURCE_ESCS = 2 # ESCs uint8 priority # Zero based priority is the connection on the Power Controller V1..Vn AKA BrickN-1 -uint16 capacity # Actual capacity of the battery [Ah] +uint16 capacity # Actual capacity of the battery [mAh] uint16 cycle_count # Number of discharge cycles the battery has experienced uint16 average_time_to_empty # Predicted remaining battery capacity based on the average rate of discharge [minutes] uint16 serial_number # Serial number of the battery pack From a8faf99ab15b0ff30747b14b0ca63872e7267152 Mon Sep 17 00:00:00 2001 From: Hamish Willee Date: Thu, 8 May 2025 12:37:29 +1000 Subject: [PATCH 05/12] Update msg/versioned/BatteryStatus.msg --- msg/versioned/BatteryStatus.msg | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/msg/versioned/BatteryStatus.msg b/msg/versioned/BatteryStatus.msg index cd4ca0158f2a..2a86390dce08 100644 --- a/msg/versioned/BatteryStatus.msg +++ b/msg/versioned/BatteryStatus.msg @@ -37,7 +37,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 [@enum WARNING] +uint8 warning # Current battery warning [@enum WARNING STATE] uint8 WARNING_NONE = 0 # No battery low voltage warning active uint8 WARNING_LOW = 1 # Low voltage warning uint8 WARNING_CRITICAL = 2 # Critical voltage, return / abort immediately From 06f56863fa9fdb80709a07a8028cdab5cc98fcbb Mon Sep 17 00:00:00 2001 From: Hamish Willee Date: Wed, 14 May 2025 13:58:25 +1000 Subject: [PATCH 06/12] Update msg/versioned/BatteryStatus.msg --- msg/versioned/BatteryStatus.msg | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/msg/versioned/BatteryStatus.msg b/msg/versioned/BatteryStatus.msg index 2a86390dce08..f73b0f6f0328 100644 --- a/msg/versioned/BatteryStatus.msg +++ b/msg/versioned/BatteryStatus.msg @@ -1,4 +1,8 @@ # Battery status +# +# Battery status information for up to four battery instances. +# These are populated from power module device drivers, and one battery updated from MAVLink. +# Battery instance information is also logged and streamed from MAVLink. uint32 MESSAGE_VERSION = 0 From e1f33322edb268e0b5265e8cf5782ac7d6bffe06 Mon Sep 17 00:00:00 2001 From: Hamish Willee Date: Thu, 22 May 2025 12:42:41 +1000 Subject: [PATCH 07/12] Units/enum/range before description --- msg/versioned/BatteryStatus.msg | 102 ++++++++++++++++---------------- 1 file changed, 51 insertions(+), 51 deletions(-) diff --git a/msg/versioned/BatteryStatus.msg b/msg/versioned/BatteryStatus.msg index f73b0f6f0328..64e2785cd4aa 100644 --- a/msg/versioned/BatteryStatus.msg +++ b/msg/versioned/BatteryStatus.msg @@ -6,76 +6,76 @@ uint32 MESSAGE_VERSION = 0 -uint64 timestamp # Time since system start [us] +uint64 timestamp # [us] Time since system start. bool connected # Whether or not a battery is connected, based on a voltage threshold -float32 voltage_v # Battery voltage [V] [@invalid 0] -float32 current_a # Battery current [A] [@invalid -1] -float32 current_average_a # Battery current average (for FW average in level flight) [A] [@invalid -1] -float32 discharged_mah # Discharged amount [mAh] [@invalid -1] -float32 remaining # Remaining capacity [@range 0,1] [@invalid -1] -float32 scale # Power scaling factor [@range 1,] [@invalid -1] -float32 time_remaining_s # Predicted time remaining until battery is empty under previous averaged load [s] [@invalid NaN] -float32 temperature # Temperature of the battery [°C] [@invalid NaN] -uint8 cell_count # Number of cells [@invalid 0] +float32 voltage_v # [V] [@invalid 0] Battery voltage. +float32 current_a # [A] [@invalid -1] Battery current. +float32 current_average_a # [A] [@invalid -1] Battery current average (for FW average in level flight). +float32 discharged_mah # [mAh] [@invalid -1] Discharged amount. +float32 remaining # [@range 0,1] [@invalid -1] Remaining capacity. +float32 scale # [@range 1,] [@invalid -1] Power scaling factor. +float32 time_remaining_s # [s] [@invalid NaN] Predicted time remaining until battery is empty under previous averaged load. +float32 temperature # [°C] [@invalid NaN] Temperature of the battery. +uint8 cell_count # [@invalid 0] Number of cells. -uint8 source # Battery source [@enum SOURCE] -uint8 SOURCE_POWER_MODULE = 0 # Power module +uint8 source # [@enum SOURCE] Battery source. +uint8 SOURCE_POWER_MODULE = 0 # Power module. uint8 SOURCE_EXTERNAL = 1 # External uint8 SOURCE_ESCS = 2 # ESCs uint8 priority # Zero based priority is the connection on the Power Controller V1..Vn AKA BrickN-1 -uint16 capacity # Actual capacity of the battery [mAh] -uint16 cycle_count # Number of discharge cycles the battery has experienced -uint16 average_time_to_empty # Predicted remaining battery capacity based on the average rate of discharge [minutes] -uint16 serial_number # Serial number of the battery pack +uint16 capacity # [mAh] Actual capacity of the battery. +uint16 cycle_count # Number of discharge cycles the battery has experienced. +uint16 average_time_to_empty # [minutes] Predicted remaining battery capacity based on the average rate of discharge. +uint16 serial_number # Serial number of the battery pack. uint16 manufacture_date # Manufacture date, part of serial number of the battery pack. Formatted as: Day + Month×32 + (Year–1980)×512 -uint16 state_of_health # State of health. FullChargeCapacity/DesignCapacity [%] [@range 0, 100]. -uint16 max_error # Max error, expected margin of error in the state-of-charge calculation [%] [@range 1, 100] +uint16 state_of_health # [%] [@range 0, 100] State of health. FullChargeCapacity/DesignCapacity. +uint16 max_error # [%] [@range 1, 100] Max error, expected margin of error in the state-of-charge calculation. uint8 id # ID number of a battery. Should be unique and consistent for the lifetime of a vehicle. 1-indexed. -uint16 interface_error # Interface error counter +uint16 interface_error # Interface error counter. -float32[14] voltage_cell_v # Battery individual cell voltages [V] [@invalid 0] -float32 max_cell_voltage_delta # Max difference between individual cell voltages +float32[14] voltage_cell_v # [V] [@invalid 0] Battery individual cell voltages. +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 +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 [@enum WARNING STATE] -uint8 WARNING_NONE = 0 # No battery low voltage warning active -uint8 WARNING_LOW = 1 # Low voltage warning -uint8 WARNING_CRITICAL = 2 # Critical voltage, return / abort immediately -uint8 WARNING_EMERGENCY = 3 # Immediate landing required -uint8 WARNING_FAILED = 4 # Battery has failed completely +uint8 warning # [@enum WARNING STATE] Current battery warning. +uint8 WARNING_NONE = 0 # No battery low voltage warning active. +uint8 WARNING_LOW = 1 # Low voltage warning. +uint8 WARNING_CRITICAL = 2 # Critical voltage, return / abort immediately. +uint8 WARNING_EMERGENCY = 3 # Immediate landing required. +uint8 WARNING_FAILED = 4 # Battery has failed completely. uint8 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 STATE_CHARGING = 7 # Battery is charging -uint16 faults # Smart battery supply status/fault flags (bitmask) for health indication. [@enum FAULT] -uint8 FAULT_DEEP_DISCHARGE = 0 # Battery has deep discharged -uint8 FAULT_SPIKES = 1 # Voltage spikes -uint8 FAULT_CELL_FAIL= 2 # One or more cells have failed -uint8 FAULT_OVER_CURRENT = 3 # Over-current -uint8 FAULT_OVER_TEMPERATURE = 4 # Over-temperature -uint8 FAULT_UNDER_TEMPERATURE = 5 # Under-temperature fault +uint16 faults # [@enum FAULT] Smart battery supply status/fault flags (bitmask) for health indication. +uint8 FAULT_DEEP_DISCHARGE = 0 # Battery has deep discharged. +uint8 FAULT_SPIKES = 1 # Voltage spikes. +uint8 FAULT_CELL_FAIL= 2 # One or more cells have failed. +uint8 FAULT_OVER_CURRENT = 3 # Over-current. +uint8 FAULT_OVER_TEMPERATURE = 4 # Over-temperature. +uint8 FAULT_UNDER_TEMPERATURE = 5 # Under-temperature fault. uint8 FAULT_INCOMPATIBLE_VOLTAGE = 6 # Vehicle voltage is not compatible with this battery (batteries on same power rail should have similar voltage). -uint8 FAULT_INCOMPATIBLE_FIRMWARE = 7 # Battery firmware is not compatible with current autopilot firmware -uint8 FAULT_INCOMPATIBLE_MODEL = 8 # Battery model is not supported by the system -uint8 FAULT_HARDWARE_FAILURE = 9 # hardware problem -uint8 FAULT_FAILED_TO_ARM = 10 # Battery had a problem while arming +uint8 FAULT_INCOMPATIBLE_FIRMWARE = 7 # Battery firmware is not compatible with current autopilot firmware. +uint8 FAULT_INCOMPATIBLE_MODEL = 8 # Battery model is not supported by the system. +uint8 FAULT_HARDWARE_FAILURE = 9 # hardware problem. +uint8 FAULT_FAILED_TO_ARM = 10 # Battery had a problem while arming. uint8 FAULT_COUNT = 11 # Counter - keep it as last element! uint8 MAX_INSTANCES = 4 -float32 full_charge_capacity_wh # The compensated battery capacity [Wh] -float32 remaining_capacity_wh # The compensated battery capacity remaining [Wh] -uint16 over_discharge_count # Number of battery overdischarge -float32 nominal_voltage # Nominal voltage of the battery pack [V] +float32 full_charge_capacity_wh # [Wh] The compensated battery capacity. +float32 remaining_capacity_wh # [Wh] The compensated battery capacity remaining. +uint16 over_discharge_count # Number of battery overdischarge. +float32 nominal_voltage # [V] Nominal voltage of the battery pack. -float32 internal_resistance_estimate # Internal resistance per cell estimate [Ohm] -float32 ocv_estimate # Open circuit voltage estimate [V] -float32 ocv_estimate_filtered # Filtered open circuit voltage estimate [V] -float32 volt_based_soc_estimate # Normalized volt based state of charge estimate [@range 0, 1] -float32 voltage_prediction # Predicted voltage [V] -float32 prediction_error # Prediction error [V] -float32 estimation_covariance_norm # Norm of the covariance matrix +float32 internal_resistance_estimate # [Ohm] Internal resistance per cell estimate. +float32 ocv_estimate # [V] Open circuit voltage estimate. +float32 ocv_estimate_filtered # [V] Filtered open circuit voltage estimate. +float32 volt_based_soc_estimate # [@range 0, 1] Normalized volt based state of charge estimate. +float32 voltage_prediction # [V] Predicted voltage. +float32 prediction_error # [V] Prediction error. +float32 estimation_covariance_norm # Norm of the covariance matrix. From 46c701fdfd948bde2c82ff41ad3b9bcb2b0b2a5b Mon Sep 17 00:00:00 2001 From: Hamish Willee Date: Thu, 5 Jun 2025 14:02:23 +1000 Subject: [PATCH 08/12] Update msg/versioned/BatteryStatus.msg --- msg/versioned/BatteryStatus.msg | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/msg/versioned/BatteryStatus.msg b/msg/versioned/BatteryStatus.msg index 64e2785cd4aa..45fbe1787ae0 100644 --- a/msg/versioned/BatteryStatus.msg +++ b/msg/versioned/BatteryStatus.msg @@ -1,4 +1,4 @@ -# Battery status +# Battery status. # # Battery status information for up to four battery instances. # These are populated from power module device drivers, and one battery updated from MAVLink. From 4d311e2e5e446807e3357d35e4bd31ccbd88c072 Mon Sep 17 00:00:00 2001 From: Hamish Willee Date: Thu, 5 Jun 2025 14:03:30 +1000 Subject: [PATCH 09/12] Update msg/versioned/BatteryStatus.msg --- msg/versioned/BatteryStatus.msg | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/msg/versioned/BatteryStatus.msg b/msg/versioned/BatteryStatus.msg index 45fbe1787ae0..913c2b84afad 100644 --- a/msg/versioned/BatteryStatus.msg +++ b/msg/versioned/BatteryStatus.msg @@ -21,8 +21,8 @@ uint8 cell_count # [@invalid 0] Number of cells. uint8 source # [@enum SOURCE] Battery source. uint8 SOURCE_POWER_MODULE = 0 # Power module. -uint8 SOURCE_EXTERNAL = 1 # External -uint8 SOURCE_ESCS = 2 # ESCs +uint8 SOURCE_EXTERNAL = 1 # External. +uint8 SOURCE_ESCS = 2 # ESCs. uint8 priority # Zero based priority is the connection on the Power Controller V1..Vn AKA BrickN-1 uint16 capacity # [mAh] Actual capacity of the battery. From 09f5e9da6daf7584c2af7a9cac9c54f8bd71eeeb Mon Sep 17 00:00:00 2001 From: Hamish Willee Date: Wed, 11 Jun 2025 13:37:51 +1000 Subject: [PATCH 10/12] Apply suggestions from code review Co-authored-by: Matthias Grob --- msg/versioned/BatteryStatus.msg | 13 ++++++------- 1 file changed, 6 insertions(+), 7 deletions(-) diff --git a/msg/versioned/BatteryStatus.msg b/msg/versioned/BatteryStatus.msg index 913c2b84afad..e60a614c9e62 100644 --- a/msg/versioned/BatteryStatus.msg +++ b/msg/versioned/BatteryStatus.msg @@ -1,19 +1,19 @@ # Battery status. # -# Battery status information for up to four battery instances. -# These are populated from power module device drivers, and one battery updated from MAVLink. -# Battery instance information is also logged and streamed from MAVLink. +# Battery status information for up to 4 battery instances. +# These are populated from power module and smart battery device drivers, and one battery updated from MAVLink. +# Battery instance information is also logged and streamed in MAVLink telemetry. uint32 MESSAGE_VERSION = 0 uint64 timestamp # [us] Time since system start. -bool connected # Whether or not a battery is connected, based on a voltage threshold +bool connected # Whether or not a battery is connected. For power modules this is based on a voltage threshold. float32 voltage_v # [V] [@invalid 0] Battery voltage. float32 current_a # [A] [@invalid -1] Battery current. float32 current_average_a # [A] [@invalid -1] Battery current average (for FW average in level flight). float32 discharged_mah # [mAh] [@invalid -1] Discharged amount. float32 remaining # [@range 0,1] [@invalid -1] Remaining capacity. -float32 scale # [@range 1,] [@invalid -1] Power scaling factor. +float32 scale # [@range 1,] [@invalid -1] Scaling factor to compensate for lower actuation power caused by voltage sag. float32 time_remaining_s # [s] [@invalid NaN] Predicted time remaining until battery is empty under previous averaged load. float32 temperature # [°C] [@invalid NaN] Temperature of the battery. uint8 cell_count # [@invalid 0] Number of cells. @@ -25,7 +25,7 @@ uint8 SOURCE_EXTERNAL = 1 # External. uint8 SOURCE_ESCS = 2 # ESCs. uint8 priority # Zero based priority is the connection on the Power Controller V1..Vn AKA BrickN-1 -uint16 capacity # [mAh] Actual capacity of the battery. +uint16 capacity # [mAh] Capacity of the battery when fully charged. uint16 cycle_count # Number of discharge cycles the battery has experienced. uint16 average_time_to_empty # [minutes] Predicted remaining battery capacity based on the average rate of discharge. uint16 serial_number # Serial number of the battery pack. @@ -47,7 +47,6 @@ uint8 WARNING_LOW = 1 # Low voltage warning. uint8 WARNING_CRITICAL = 2 # Critical voltage, return / abort immediately. uint8 WARNING_EMERGENCY = 3 # Immediate landing required. uint8 WARNING_FAILED = 4 # Battery has failed completely. - uint8 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 STATE_CHARGING = 7 # Battery is charging From 10af85e6227e98099c525b6d534d98c0cf3aeb85 Mon Sep 17 00:00:00 2001 From: Hamish Willee Date: Wed, 11 Jun 2025 13:38:55 +1000 Subject: [PATCH 11/12] MOve MAX_INSTANCES to top --- msg/versioned/BatteryStatus.msg | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/msg/versioned/BatteryStatus.msg b/msg/versioned/BatteryStatus.msg index e60a614c9e62..ebbddf94eff8 100644 --- a/msg/versioned/BatteryStatus.msg +++ b/msg/versioned/BatteryStatus.msg @@ -5,6 +5,7 @@ # Battery instance information is also logged and streamed in MAVLink telemetry. uint32 MESSAGE_VERSION = 0 +uint8 MAX_INSTANCES = 4 uint64 timestamp # [us] Time since system start. bool connected # Whether or not a battery is connected. For power modules this is based on a voltage threshold. @@ -64,8 +65,6 @@ uint8 FAULT_HARDWARE_FAILURE = 9 # hardware problem. uint8 FAULT_FAILED_TO_ARM = 10 # Battery had a problem while arming. uint8 FAULT_COUNT = 11 # Counter - keep it as last element! -uint8 MAX_INSTANCES = 4 - float32 full_charge_capacity_wh # [Wh] The compensated battery capacity. float32 remaining_capacity_wh # [Wh] The compensated battery capacity remaining. uint16 over_discharge_count # Number of battery overdischarge. From 2af2b04b5e90b39de46ac19042c8f4ef8de39dfd Mon Sep 17 00:00:00 2001 From: Hamish Willee Date: Thu, 12 Jun 2025 11:31:06 +1000 Subject: [PATCH 12/12] Fix up full stops --- msg/versioned/BatteryStatus.msg | 116 ++++++++++++++++---------------- 1 file changed, 58 insertions(+), 58 deletions(-) diff --git a/msg/versioned/BatteryStatus.msg b/msg/versioned/BatteryStatus.msg index ebbddf94eff8..f8f9e3f12dbe 100644 --- a/msg/versioned/BatteryStatus.msg +++ b/msg/versioned/BatteryStatus.msg @@ -1,4 +1,4 @@ -# Battery status. +# Battery status # # Battery status information for up to 4 battery instances. # These are populated from power module and smart battery device drivers, and one battery updated from MAVLink. @@ -7,73 +7,73 @@ uint32 MESSAGE_VERSION = 0 uint8 MAX_INSTANCES = 4 -uint64 timestamp # [us] Time since system start. +uint64 timestamp # [us] Time since system start bool connected # Whether or not a battery is connected. For power modules this is based on a voltage threshold. -float32 voltage_v # [V] [@invalid 0] Battery voltage. -float32 current_a # [A] [@invalid -1] Battery current. -float32 current_average_a # [A] [@invalid -1] Battery current average (for FW average in level flight). -float32 discharged_mah # [mAh] [@invalid -1] Discharged amount. -float32 remaining # [@range 0,1] [@invalid -1] Remaining capacity. -float32 scale # [@range 1,] [@invalid -1] Scaling factor to compensate for lower actuation power caused by voltage sag. -float32 time_remaining_s # [s] [@invalid NaN] Predicted time remaining until battery is empty under previous averaged load. -float32 temperature # [°C] [@invalid NaN] Temperature of the battery. -uint8 cell_count # [@invalid 0] Number of cells. +float32 voltage_v # [V] [@invalid 0] Battery voltage +float32 current_a # [A] [@invalid -1] Battery current +float32 current_average_a # [A] [@invalid -1] Battery current average (for FW average in level flight) +float32 discharged_mah # [mAh] [@invalid -1] Discharged amount +float32 remaining # [@range 0,1] [@invalid -1] Remaining capacity +float32 scale # [@range 1,] [@invalid -1] Scaling factor to compensate for lower actuation power caused by voltage sag +float32 time_remaining_s # [s] [@invalid NaN] Predicted time remaining until battery is empty under previous averaged load +float32 temperature # [°C] [@invalid NaN] Temperature of the battery +uint8 cell_count # [@invalid 0] Number of cells -uint8 source # [@enum SOURCE] Battery source. -uint8 SOURCE_POWER_MODULE = 0 # Power module. -uint8 SOURCE_EXTERNAL = 1 # External. -uint8 SOURCE_ESCS = 2 # ESCs. +uint8 source # [@enum SOURCE] Battery source +uint8 SOURCE_POWER_MODULE = 0 # Power module +uint8 SOURCE_EXTERNAL = 1 # External +uint8 SOURCE_ESCS = 2 # ESCs uint8 priority # Zero based priority is the connection on the Power Controller V1..Vn AKA BrickN-1 -uint16 capacity # [mAh] Capacity of the battery when fully charged. -uint16 cycle_count # Number of discharge cycles the battery has experienced. -uint16 average_time_to_empty # [minutes] Predicted remaining battery capacity based on the average rate of discharge. -uint16 serial_number # Serial number of the battery pack. +uint16 capacity # [mAh] Capacity of the battery when fully charged +uint16 cycle_count # Number of discharge cycles the battery has experienced +uint16 average_time_to_empty # [minutes] Predicted remaining battery capacity based on the average rate of discharge +uint16 serial_number # Serial number of the battery pack uint16 manufacture_date # Manufacture date, part of serial number of the battery pack. Formatted as: Day + Month×32 + (Year–1980)×512 -uint16 state_of_health # [%] [@range 0, 100] State of health. FullChargeCapacity/DesignCapacity. -uint16 max_error # [%] [@range 1, 100] Max error, expected margin of error in the state-of-charge calculation. -uint8 id # ID number of a battery. Should be unique and consistent for the lifetime of a vehicle. 1-indexed. -uint16 interface_error # Interface error counter. +uint16 state_of_health # [%] [@range 0, 100] State of health. FullChargeCapacity/DesignCapacity +uint16 max_error # [%] [@range 1, 100] Max error, expected margin of error in the state-of-charge calculation +uint8 id # ID number of a battery. Should be unique and consistent for the lifetime of a vehicle. 1-indexed +uint16 interface_error # Interface error counter -float32[14] voltage_cell_v # [V] [@invalid 0] Battery individual cell voltages. -float32 max_cell_voltage_delta # Max difference between individual cell voltages. +float32[14] voltage_cell_v # [V] [@invalid 0] Battery individual cell voltages +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. +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 # [@enum WARNING STATE] Current battery warning. -uint8 WARNING_NONE = 0 # No battery low voltage warning active. -uint8 WARNING_LOW = 1 # Low voltage warning. -uint8 WARNING_CRITICAL = 2 # Critical voltage, return / abort immediately. -uint8 WARNING_EMERGENCY = 3 # Immediate landing required. -uint8 WARNING_FAILED = 4 # Battery has failed completely. -uint8 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 warning # [@enum WARNING STATE] Current battery warning +uint8 WARNING_NONE = 0 # No battery low voltage warning active +uint8 WARNING_LOW = 1 # Low voltage warning +uint8 WARNING_CRITICAL = 2 # Critical voltage, return / abort immediately +uint8 WARNING_EMERGENCY = 3 # Immediate landing required +uint8 WARNING_FAILED = 4 # Battery has failed completely +uint8 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 STATE_CHARGING = 7 # Battery is charging -uint16 faults # [@enum FAULT] Smart battery supply status/fault flags (bitmask) for health indication. -uint8 FAULT_DEEP_DISCHARGE = 0 # Battery has deep discharged. -uint8 FAULT_SPIKES = 1 # Voltage spikes. -uint8 FAULT_CELL_FAIL= 2 # One or more cells have failed. -uint8 FAULT_OVER_CURRENT = 3 # Over-current. -uint8 FAULT_OVER_TEMPERATURE = 4 # Over-temperature. -uint8 FAULT_UNDER_TEMPERATURE = 5 # Under-temperature fault. -uint8 FAULT_INCOMPATIBLE_VOLTAGE = 6 # Vehicle voltage is not compatible with this battery (batteries on same power rail should have similar voltage). -uint8 FAULT_INCOMPATIBLE_FIRMWARE = 7 # Battery firmware is not compatible with current autopilot firmware. -uint8 FAULT_INCOMPATIBLE_MODEL = 8 # Battery model is not supported by the system. -uint8 FAULT_HARDWARE_FAILURE = 9 # hardware problem. -uint8 FAULT_FAILED_TO_ARM = 10 # Battery had a problem while arming. -uint8 FAULT_COUNT = 11 # Counter - keep it as last element! +uint16 faults # [@enum FAULT] Smart battery supply status/fault flags (bitmask) for health indication +uint8 FAULT_DEEP_DISCHARGE = 0 # Battery has deep discharged +uint8 FAULT_SPIKES = 1 # Voltage spikes +uint8 FAULT_CELL_FAIL= 2 # One or more cells have failed +uint8 FAULT_OVER_CURRENT = 3 # Over-current +uint8 FAULT_OVER_TEMPERATURE = 4 # Over-temperature +uint8 FAULT_UNDER_TEMPERATURE = 5 # Under-temperature fault +uint8 FAULT_INCOMPATIBLE_VOLTAGE = 6 # Vehicle voltage is not compatible with this battery (batteries on same power rail should have similar voltage) +uint8 FAULT_INCOMPATIBLE_FIRMWARE = 7 # Battery firmware is not compatible with current autopilot firmware +uint8 FAULT_INCOMPATIBLE_MODEL = 8 # Battery model is not supported by the system +uint8 FAULT_HARDWARE_FAILURE = 9 # Hardware problem +uint8 FAULT_FAILED_TO_ARM = 10 # Battery had a problem while arming +uint8 FAULT_COUNT = 11 # Counter. Keep this as last element -float32 full_charge_capacity_wh # [Wh] The compensated battery capacity. -float32 remaining_capacity_wh # [Wh] The compensated battery capacity remaining. -uint16 over_discharge_count # Number of battery overdischarge. -float32 nominal_voltage # [V] Nominal voltage of the battery pack. +float32 full_charge_capacity_wh # [Wh] Compensated battery capacity +float32 remaining_capacity_wh # [Wh] Compensated battery capacity remaining +uint16 over_discharge_count # Number of battery overdischarge +float32 nominal_voltage # [V] Nominal voltage of the battery pack -float32 internal_resistance_estimate # [Ohm] Internal resistance per cell estimate. -float32 ocv_estimate # [V] Open circuit voltage estimate. -float32 ocv_estimate_filtered # [V] Filtered open circuit voltage estimate. -float32 volt_based_soc_estimate # [@range 0, 1] Normalized volt based state of charge estimate. -float32 voltage_prediction # [V] Predicted voltage. -float32 prediction_error # [V] Prediction error. -float32 estimation_covariance_norm # Norm of the covariance matrix. +float32 internal_resistance_estimate # [Ohm] Internal resistance per cell estimate +float32 ocv_estimate # [V] Open circuit voltage estimate +float32 ocv_estimate_filtered # [V] Filtered open circuit voltage estimate +float32 volt_based_soc_estimate # [@range 0, 1] Normalized volt based state of charge estimate +float32 voltage_prediction # [V] Predicted voltage +float32 prediction_error # [V] Prediction error +float32 estimation_covariance_norm # Norm of the covariance matrix