PX4-Autopilot icon indicating copy to clipboard operation
PX4-Autopilot copied to clipboard

Online battery internal resistance estimation

Open chfriedrich98 opened this issue 1 year ago • 17 comments

Solved Problem

The volt-based estimation of the state of charge (SoC) currently uses a standard value for the internal resistance (IR) of the battery to compensate drops in the measurement of the voltage due to current draw. If a battery is used that does not conform to this standard value it can lead to over/-underestimation and fluctuations of the volt-based SoC. This PR implements an algorithm for online estimation of the battery IR to improve the volt-based SoC estimation.

Solution

The algorithm is based on an approximation of the battery dynamics with an equivalent circuit model (ECM) consisting of the open-circuit voltage (OCV) and the IR of the battery: Screenshot from 2024-05-31 11-03-46 The open-circuit voltage is the "actual voltage" of the battery which is used for the volt-based SoC estimation. The ECM leads to the following equation:

$$ V=V_{oc} - R_{int} \cdot I $$

With:

Symbol Description Unit
$V$ Measured voltage V
$V_{oc}$ Open-circuit voltage V
$I$ Measured current A
$R_{int}$ Internal resistance Ohm

This equation includes two measurements $V$, $I$ and two unknowns $V_{oc}$, $R_{int}$.

To estimate the two unknown parameters a recursive least squares (RLS) algorithm is used: The equation is brought into the standard form for RLS:

$$ V=\underbrace{\begin{pmatrix}V_{oc} & R_{int}\end{pmatrix}}_{\theta^T} \underbrace{\binom{1}{-I}}_x $$

With:

Symbol Description Dimension
$\theta$ Parameter estimates $\mathbb{R}^{2\times 1}$
$x$ Input vector $\mathbb{R}^{2\times 1}$

The algorithm is driven by the error $e_k$ between the measured voltage $V_k$ and the predicted voltage $\hat{V}_k$ at time $k$:

$$ e_k = V_k - \hat{V}_k = V_k - \theta^T_k x_k $$

The gain vector $\gamma_k$ and the error $e_k$ are used to update the parameter estimates:

$$ \begin{align} \gamma_k &= \frac{P_k x_k}{\lambda + x^T_k P_k x_k} \ \theta_{k+1} &= \theta_{k} + \gamma_k \cdot e_k \end{align} $$

With:

Symbol Description Dimension
$e_k$ Estimation error $\mathbb{R}$
$\gamma_k$ Gain vector $\mathbb{R}^{2\times 1}$
$P_k$ Inverse covariance matrix $\mathbb{R}^{2\times 2}$
$\lambda$ Forgetting factor $\mathbb{R}$

$P_k$ is an indicator of the uncertainty of the estimation and is updated on each iteration:

$$ P_{k+1} = \frac{1}{\lambda}(P_k - \gamma_k x^T_k P_k) $$

$\lambda \in [0, 1]$ is the tuning parameter of the RLS algorithm and sets how much old data is weighted (closer to 1 means more weight on old data).

To make the algorithm more stable the estimate is only updated if the norm of the new covariance matrix $P_{k+1}$ is smaller than of the old covariance matrix $P_k$.

The algorithm is implemented in the battery library and logs relevant values in the BatteryStatus.msg which include:

Variable Description Unit
internal_resistance_estimate Internal resistance per cell estimate Ohm
ocv_estimate OCV estimate V
ocv_estimate_filtered Filtered OCV estimate V
volt_based_soc_estimate [0, 1] Normalized volt based state of charge estimate -
voltage_prediction Predicted voltage based on OCV and IR estimate V
prediction_error Difference between the predicted and measured voltage V
estimation_covariance_norm Norm of the covariance matrix -

The value that is actually used for the SoC estimation is the internal_resistance_estimate.

The estimator values will be used if the internal resistance parameter BAT${i}_R_INTERNAL is set to a negative value. If this parameter is set to a positive value than that value will be used instead. If the parameter is set to 0, then there will be no load compensation. The estimator will run and log everything even if the values are not used s.t. it can be analyzed in the logs what the estimator 'would have done' and compare it to the default (or manually set) IR.

In addition to the implementation of the online estimation there is also a python file (src/lib/battery/int_res_est_replay.py) that can run the algorithm on already recorded flight logs. This enables offline tuning of the algorithm aswell as an option to find a good value for the internal resistance which can then be manually set to avoid having to run the algorithm online.

Changelog Entry

For release notes:

Feature: Introduce online estimation for battery internal resistance

Alternatives

Open to any suggestions

Test coverage

  • Tests on a variety of flight logs run offline with the python file.
  • Real tests of the online estimation:
    • Quadrotor with 4S LIPO battery (x500): https://review.px4.io/plot_app?log=2bdc2d7a-1012-4080-a43f-c519252bbb37
    • Titltrotor VTOL with 6S LIPO battery: https://review.px4.io/plot_app?log=b2583d5e-09d2-4282-9613-bd903c0a6538, https://review.px4.io/plot_app?log=b9ec3122-afff-44a3-9cb1-8e8e0e04b811).
    • Rover with 3S LIPO battery: https://review.px4.io/plot_app?log=97dad38d-df0f-4a7b-8532-5bd1fc691342
    • Quadrotor with 6S LION battery (Droneblocks DEXI 5): https://review.px4.io/plot_app?log=4771723d-779d-47f4-bf61-351b8a7ca6bb, https://review.px4.io/plot_app?log=80260811-cdce-40c3-a2ba-3916526964d0 (thanks @AlexKlimaj).
    • (More to come)

Context

Related links, screenshot before/after, video

chfriedrich98 avatar May 30 '24 10:05 chfriedrich98

I made a commit to remove the throttle based load compensation because it's bound to produce unpredictable results instead of making the state of charge estimate more accurate.

@AlexKlimaj I'd like to ask your feedback since you added the only airframe containing this parameter here: https://github.com/PX4/PX4-Autopilot/commit/1b1479a92b61ca700b69f34da531674a4fcf4d8c#diff-75cd0cb06fb521e88d7b59ba47074ea19b2a21fa4997aad085ff23e549434b35R28 Was this a workaround? Did it produce accurate results? Does the board not have current sensing?

MaEtUgR avatar Jun 17 '24 12:06 MaEtUgR

I made a commit to remove the throttle based load compensation because it's bound to produce unpredictable results instead of making the state of charge estimate more accurate.

@AlexKlimaj I'd like to ask your feedback since you added the only airframe containing this parameter here: 1b1479a#diff-75cd0cb06fb521e88d7b59ba47074ea19b2a21fa4997aad085ff23e549434b35R28 Was this a workaround? Did it produce accurate results? Does the board not have current sensing?

The airframe uses a Lion battery that has a high voltage drop under load.

Here is an example. https://review.px4.io/plot_app?log=33a8861c-22a9-4f52-bf8c-0d62f2500320

AlexKlimaj avatar Jun 17 '24 13:06 AlexKlimaj

We also use a lion battery with higher v drop under load. Lots of logs if needed.

ryanjAA avatar Jun 17 '24 13:06 ryanjAA

I made a commit to remove the throttle based load compensation because it's bound to produce unpredictable results instead of making the state of charge estimate more accurate.

@AlexKlimaj I'd like to ask your feedback since you added the only airframe containing this parameter here:

https://github.com/PX4/PX4-Autopilot/commit/1b1479a92b61ca700b69f34da531674a4fcf4d8c#diff-75cd0cb06fb521e88d7b59ba47074ea19b2a21fa4997aad085ff23e549434b35R28

Was this a workaround? Did it produce accurate results? Does the board not have current sensing?

@MaEtUgR What the reasoning for your view that throttle based load compensation will produce unpredictable results?

ryanjAA avatar Jun 17 '24 13:06 ryanjAA

@AlexKlimaj, @ryanjAA The internal resistance is also used to compensate load drops, the reason why this might've not worked well with lion batteries is because the default value is set to 5mOhm. Lion batteries generally have higher IR values, an online estimation algorithm would be able to account for that and lead to better load compensation. e.g. when using the current/voltage data from your log @AlexKlimaj with the estimation algorithm: Screenshot from 2024-06-17 16-30-21

chfriedrich98 avatar Jun 17 '24 14:06 chfriedrich98

Looks good to me. I like this more than trying to estimate the param.

AlexKlimaj avatar Jun 17 '24 14:06 AlexKlimaj

We also use a lion battery with higher v drop under load. Lots of logs if needed.

@ryanjAA Would love to have some logs to test the algorithm!

chfriedrich98 avatar Jun 17 '24 14:06 chfriedrich98

We also use a lion battery with higher v drop under load. Lots of logs if needed.

@ryanjAA Would love to have some logs to test the algorithm!

https://review.px4.io/plot_app?log=b81096bc-1172-400e-a774-d99635c548ab

https://review.px4.io/plot_app?log=d26f63a2-28f0-40c7-b81a-554f285d87b1

https://review.px4.io/plot_app?log=fead427b-23bf-426b-8138-30764197aeaf https://review.px4.io/plot_app?log=6efcab43-8f73-4e8a-81a4-e67a697f29fd https://review.px4.io/plot_app?log=a20c78a1-9737-43af-b48b-08cdbe895830 https://review.px4.io/plot_app?log=e3852b37-1f69-481d-97b4-21625e77f09c https://review.px4.io/plot_app?log=85e7018e-6980-4ab5-9efb-29247b1e8a40 https://review.px4.io/plot_app?log=9fd4e98c-04af-493b-8387-34a6eac902cb https://review.px4.io/plot_app?log=4baefb1b-15d1-440e-b05f-526d58552fa5 https://review.px4.io/plot_app?log=6ddeef40-9571-4a8c-93a2-92b7d70eae46 https://review.px4.io/plot_app?log=755cb3f0-10c8-4f3f-8c24-c1a79b08ad87 https://review.px4.io/plot_app?log=d0fd56d0-e8f3-46fb-8384-62a2c50a91f7 https://review.px4.io/plot_app?log=77c5b3b3-ea2f-4076-94ae-0dcccb28e71e https://review.px4.io/plot_app?log=a03594eb-b403-4b60-8569-3c227f4d07d6 https://review.px4.io/plot_app?log=939e4474-6daa-43a9-8fac-d8d98f07bc17 https://review.px4.io/plot_app?log=57413060-21da-4ab2-974f-016fbc8ba25c https://review.px4.io/plot_app?log=93c5fae3-9280-4309-9f69-c17c75ee8fa6 https://review.px4.io/plot_app?log=08df4199-bccd-4745-8768-859f3a802ec8 https://review.px4.io/plot_app?log=5c3da1c5-e1ee-4ddd-82ba-7942f3d36b05 https://review.px4.io/plot_app?log=ef2e27f1-7329-4db7-9373-dd2bf2b70ccc https://review.px4.io/plot_app?log=d32f3cb8-dc3e-46dc-aad1-1607cc1bb895 https://review.px4.io/plot_app?log=353f4df5-1405-4d38-a6ef-17faf974cd4f https://review.px4.io/plot_app?log=4b9da507-81ac-4afa-8814-c204da6f7b56 https://review.px4.io/plot_app?log=131f84d2-639a-44b8-b87d-09c52dc039fc https://review.px4.io/plot_app?log=f7130c9e-0a0d-421f-927f-e15f1c9736ee https://review.px4.io/plot_app?log=48b6def5-fcd1-441f-88e6-a29e1602f3b2 https://review.px4.io/plot_app?log=300c4368-3353-4eef-940e-b4c1221cb2f7 https://review.px4.io/plot_app?log=ba4f9c24-b70e-4da5-a7c5-805e1e0fcdb9 https://review.px4.io/plot_app?log=a7442044-0512-4f27-9f01-6abe8922d4ee http://files.appliedaeronautics.com:5006/plot_app?log=3918377b-8858-4582-8956-ceabb818cb97 https://review.px4.io/plot_app?log=582ad5c8-a030-4e1c-83cc-8b9e12e7adaf https://review.px4.io/plot_app?log=ab7e959e-636c-4667-bf6e-72fc6ee46fdc https://review.px4.io/plot_app?log=927b658a-da8c-4260-9e2d-ac9461f042be https://review.px4.io/plot_app?log=300c4368-3353-4eef-940e-b4c1221cb2f7 https://review.px4.io/plot_app?log=4ef94126-6c11-421d-9d9d-91084c0ccad9 https://review.px4.io/plot_app?log=8551e5c9-2262-4ce5-b339-a4c1e4344ba8 https://review.px4.io/plot_app?log=ef794429-7b0c-4452-946c-0024cc90d565 https://review.px4.io/plot_app?log=8551e5c9-2262-4ce5-b339-a4c1e4344ba8 https://review.px4.io/plot_app?log=ef794429-7b0c-4452-946c-0024cc90d565 https://review.px4.io/plot_app?log=0cfb33f6-a8ad-436a-9aa9-dc46408b5766 https://review.px4.io/plot_app?log=ea406bd3-3169-4734-b9af-1ad5303d2984 https://review.px4.io/plot_app?log=ac0775d6-84c2-4def-8641-7ecaafd7547e https://review.px4.io/plot_app?log=7939dcb5-2a7d-4a49-ac00-d5588ec22934 https://review.px4.io/plot_app?log=700e86d5-b7d9-482f-b7e9-9761c6238048 https://review.px4.io/plot_app?log=6a67a36a-ab61-4672-945d-b4a25b0c0494 https://logs.px4.io/plot_app?log=c52a816e-3cf9-42e4-9384-a3946a59504f https://review.px4.io/plot_app?log=2053c052-d1d7-4337-878d-7bb9f795c105 https://review.px4.io/plot_app?log=6a67a36a-ab61-4672-945d-b4a25b0c0494 https://review.px4.io/plot_app?log=97186db0-1043-4cb8-95e6-7dd1853bdf81 https://review.px4.io/plot_app?log=f5fd2ecf-8b1f-4c77-baab-ab556bb2a6c0 https://review.px4.io/plot_app?log=5eed8abb-02a9-47c4-bc85-56d0ac8f684d https://logs.px4.io/plot_app?log=bd506e50-3ba7-4713-b212-7bb9e0f7f6ef https://logs.px4.io/plot_app?log=aba3ca67-7721-4cc4-ac94-1b3a4c9f639e https://logs.px4.io/plot_app?log=9cd327e1-9909-4896-9159-b05141cc0b48 https://review.px4.io/plot_app?log=c5e273cf-55d3-4177-b32f-e3d7189ee586 https://logs.px4.io/plot_app?log=5877bc88-3de6-43e8-b72e-14d9711ebd94 https://logs.px4.io/plot_app?log=2b2e71b3-b6cd-4338-bc20-787e38e3c38b https://review.px4.io/plot_app?log=d5fa325c-526e-4f6d-9784-4553b0aa3412 https://logs.px4.io/plot_app?log=a22c4f4e-8c96-4630-a147-75392b285b14 https://logs.px4.io/plot_app?log=c52a816e-3cf9-42e4-9384-a3946a59504f https://logs.px4.io/plot_app?log=875a0417-ae32-4711-8eac-168f7dadc345 https://logs.px4.io/plot_app?log=57e5f314-84b3-4504-9818-75c409f64841 https://logs.px4.io/plot_app?log=20aa404c-ca21-4ace-a9ad-e332b4e1ac4a https://logs.px4.io/plot_app?log=2408c4ea-6203-4e05-ba3d-f5b194f49ed7

All with li-ion.

ryanjAA avatar Jun 17 '24 15:06 ryanjAA

Is this still a draft or ready for merge?

AlexKlimaj avatar Jun 18 '24 21:06 AlexKlimaj

Is this still a draft or ready for merge?

@AlexKlimaj The code is in a "near finished state" but I've been doing and will continue to do some more hardware tests to properly test the algorithm.

chfriedrich98 avatar Jun 19 '24 06:06 chfriedrich98

@ryanjAA Even though the measurements appear to be considerably more noisy in your logs, the estimator is still able to compensate the load drops quite well: image And this can be further improved by filtering the ocv estimate: image

chfriedrich98 avatar Jun 19 '24 14:06 chfriedrich98

There can be multiple instances of Battery, at a minimum you should use uORB::PublicationMulti<internal_resistance_estimator_s> for the internal resistance publication.

We probably also need a mechanism to make this optional.

dagar avatar Jun 19 '24 17:06 dagar

Thanks for the input @dagar!

There can be multiple instances of Battery, at a minimum you should use uORB::PublicationMulti<internal_resistance_estimator_s> for the internal resistance publication.

Agreed, I'll look into it. One idea that comes to mind is to just merge the InternalResistanceEstimator.msg into the BatteryStatus.msg since they are closely related anyway.

We probably also need a mechanism to make this optional.

With this implementation there are 3 options for the user:

  1. Manually set a positive IR value -> This will then be used instead of the estimator.
  2. Set the IR value to 0 -> Disables load compensation completely.
  3. Set the IR value to something negativ -> Estimator values will be used.

The estimator will run with all 3 options, to give the user the oportunity to see in the logs what the estimator "would have done" without actually using it. I think this option is useful especially at the beginning, but could be changed later s.t. the estimator only runs with option 3.

chfriedrich98 avatar Jun 20 '24 06:06 chfriedrich98

Rebased you PR on main and did a couple of flights to completely drain a battery. Behavior was great. % only increased 2-3% after landing.

https://review.px4.io/plot_app?log=4771723d-779d-47f4-bf61-351b8a7ca6bb https://review.px4.io/plot_app?log=80260811-cdce-40c3-a2ba-3916526964d0

image image

AlexKlimaj avatar Jun 26 '24 17:06 AlexKlimaj

Thank you very much for testing the algorithm @AlexKlimaj !

Rebased you PR on main and did a couple of flights to completely drain a battery. Behavior was great. % only increased 2-3% after landing.

I had a look at the logs and the results look really good!

Do we want to make this the default behavior? Update BAT${i}_R_INTERNAL defaults to -0.005?

Eventually this is the goal, I think it will be a big improvement especially for people that are not familiar with batteries and are looking for a more 'plug-and-play' solution. My thinking right now is to leave it as is and give people the opportunity to test or simply observe what the estimator 'would have done' in logs (This is also why the estimator runs in the background even if the estimated values are not used). Once I have received a sufficient amount of logs I would open a new PR to make this the default behaviour.

chfriedrich98 avatar Jun 27 '24 07:06 chfriedrich98

Here are some more logs from today on two different vehicles.

https://review.px4.io/plot_app?log=524e35d3-a158-4ad0-9159-c1b9aab2c5db https://review.px4.io/plot_app?log=9fd1d217-ab0c-444d-8bb7-a336c2ada318

https://review.px4.io/plot_app?log=70e6202e-83ff-4137-9092-3642b18e62e3 https://review.px4.io/plot_app?log=aa8bd99a-8e58-44af-8584-e768f8bec2b0 https://review.px4.io/plot_app?log=7410a7ef-5470-497f-81d5-0cf225d042d5

AlexKlimaj avatar Jun 27 '24 19:06 AlexKlimaj

https://review.px4.io/plot_app?log=2c501c07-b2ae-4628-bdbe-bdb65b8c9380

AlexKlimaj avatar Jun 28 '24 18:06 AlexKlimaj

Rebased you PR on main and did a couple of flights to completely drain a battery. Behavior was great. % only increased 2-3% after landing.

https://review.px4.io/plot_app?log=4771723d-779d-47f4-bf61-351b8a7ca6bb https://review.px4.io/plot_app?log=80260811-cdce-40c3-a2ba-3916526964d0

image image

Out of curiosity, how much increase would you get previously for comparison?

ryanjAA avatar Jul 01 '24 11:07 ryanjAA

Rebased you PR on main and did a couple of flights to completely drain a battery. Behavior was great. % only increased 2-3% after landing. https://review.px4.io/plot_app?log=4771723d-779d-47f4-bf61-351b8a7ca6bb https://review.px4.io/plot_app?log=80260811-cdce-40c3-a2ba-3916526964d0 image image

Out of curiosity, how much increase would you get previously for comparison?

30-40% before

AlexKlimaj avatar Jul 01 '24 15:07 AlexKlimaj

Maybe im missing something @chfriedrich98 but this log https://review.px4.io/plot_app?log=0e63b40b-adda-4a21-9b04-599d1dadbb94 says when I run the batt estimator that its soc is zero quite prematurely.

Screenshot 2024-07-01 at 8 47 56 PM

ryanjAA avatar Jul 02 '24 01:07 ryanjAA

ahh it's set for lipo. ok so -e and set end voltage. @AlexKlimaj what are you cutting off at? 2.5v (per cell) is allowable but in my experience if you really want to take it that low you need throttle based compensation because you lose so much power (or you need to run a 7s if you have a 6s setup, etc etc)

also, why are we still using 4.05 as full voltage? is that really what people still think is correct as the assumed full v per cell under load? Shouldn't we keep it at 4.2 (higher I guess for HV) and then compensate from there?

ryanjAA avatar Jul 02 '24 03:07 ryanjAA

@ryanjAA

ahh it's set for lipo.

Ideally I would like to get the parameters directly from the log s.t. you don't have to set it manually in the replay file, but I've not gotten around to figuring out how that works yet.

also, why are we still using 4.05 as full voltage? is that really what people still think is correct as the assumed full v per cell under load? Shouldn't we keep it at 4.2 (higher I guess for HV) and then compensate from there?

The default max/min per cell voltages were set to [3.6V, 4.05V] because that is approximately the range in which the OCV <-> SOC relationship is linear for many consumer grade LIPO batteries under "normal" conditions (of course this can still vary a lot for different batteries). I think setting the default to 4.2V is not a bad idea, since it is the actual max per cell voltage for most batteries and the nonlinearity in the OCV <-> SOC curve at the beginning is not an issue, only the steep drop off at the lower limit.

chfriedrich98 avatar Jul 02 '24 07:07 chfriedrich98

rebased on main and squashed

chfriedrich98 avatar Jul 02 '24 14:07 chfriedrich98

Ideally I would like to get the parameters directly from the log s.t. you don't have to set it manually in the replay file, but I've not gotten around to figuring out how that works yet.

Ok. I actually added that in on local branch last night so let me push that back when getting to a computer.

ryanjAA avatar Jul 02 '24 15:07 ryanjAA

ahh it's set for lipo. ok so -e and set end voltage. @AlexKlimaj what are you cutting off at? 2.5v (per cell) is allowable but in my experience if you really want to take it that low you need throttle based compensation because you lose so much power (or you need to run a 7s if you have a 6s setup, etc etc)

also, why are we still using 4.05 as full voltage? is that really what people still think is correct as the assumed full v per cell under load? Shouldn't we keep it at 4.2 (higher I guess for HV) and then compensate from there?

I've been using 3.3V for empty. Maybe we set full to 4.15V.

AlexKlimaj avatar Jul 02 '24 15:07 AlexKlimaj

ahh it's set for lipo. ok so -e and set end voltage. @AlexKlimaj what are you cutting off at? 2.5v (per cell) is allowable but in my experience if you really want to take it that low you need throttle based compensation because you lose so much power (or you need to run a 7s if you have a 6s setup, etc etc) also, why are we still using 4.05 as full voltage? is that really what people still think is correct as the assumed full v per cell under load? Shouldn't we keep it at 4.2 (higher I guess for HV) and then compensate from there?

I've been using 3.3V for empty. Maybe we set full to 4.15V.

3.3 is super conservative for lion. I use 2.95 and it’s not ever battery safety. It’s about the serious v drop around 2.5 (or just above it). Do you have anything curves from your smart batt work? Usually I don’t ever let it get that low but now with this, definitely will enable tighter controls on when to land.

Only immediate issue with 4.15 (there really isn’t one) is if you replay an existing log it skews them because internal assumes 4.05. New logs would be fine. I’m mostly interested in why we are at 4.05. 4.20 makes sense since that’s what full v is.

Not sure why we magic number it.

ryanjAA avatar Jul 02 '24 16:07 ryanjAA

The problem is every cell curve is slightly different. With this open circuit voltage being the default, we can stop guessing about the voltage under load and users can set the empty voltage to the cell datasheet curve. But we should be conservative with the default.

AlexKlimaj avatar Jul 02 '24 16:07 AlexKlimaj

This was all working when I tested the PR last week. But I just flashed main and battery_status in QGC is broken.

image image

nsh> ina226 status
INFO  [SPI_I2C] Running on I2C Bus 3, Address 0x41
ina226_read: 2647 events, 2731588us elapsed, 1031.96us avg, min 984us max 1543us 53.623us rms
ina226_com_err: 0 events
poll interval:  99993 
nsh> listener battery_status

TOPIC: battery_status
 battery_status
    timestamp: 273877327 (0.097700 seconds ago)
    voltage_v: 24.85125
    voltage_filtered_v: 0.00000
    current_a: 0.25024
    current_filtered_a: 0.00000
    current_average_a: 13.00000
    discharged_mah: 18.47162
    remaining: 0.99537
    scale: 1.00000
    time_remaining_s: 1102.56799
    temperature: nan
    voltage_cell_v: [0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000, 0.00000]
    max_cell_voltage_delta: 0.00000
    custom_faults: 0
    average_power: 0.00000
    available_energy: 0.00000
    full_charge_capacity_wh: 0.00000
    remaining_capacity_wh: 0.00000
    design_capacity: 0.00000
    nominal_voltage: 0.00000
    internal_resistance_estimate: 0.00499
    ocv_estimate: 24.85874
    ocv_estimate_filtered: 24.85884
    volt_based_soc_estimate: 1.00000
    voltage_prediction: 24.85125
    prediction_error: 0.00000
    estimation_covariance_norm: 0.79976
    capacity: 4000
    cycle_count: 0
    average_time_to_empty: 0
    serial_number: 0
    manufacture_date: 0
    state_of_health: 0
    max_error: 0
    interface_error: 0
    faults: 0
    average_time_to_full: 0
    over_discharge_count: 0
    connected: True
    cell_count: 6
    source: 0
    priority: 0
    id: 1
    is_powering_off: False
    is_required: False
    warning: 0
    mode: 0

nsh> 

AlexKlimaj avatar Jul 02 '24 18:07 AlexKlimaj

@AlexKlimaj Is it just the voltage display that is broken?

chfriedrich98 avatar Jul 02 '24 19:07 chfriedrich98

https://github.com/PX4/PX4-Autopilot/pull/23350

AlexKlimaj avatar Jul 02 '24 19:07 AlexKlimaj