Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Battery Estimation Corrections #8153

Merged
merged 11 commits into from
Jan 11, 2018
Merged

Battery Estimation Corrections #8153

merged 11 commits into from
Jan 11, 2018

Conversation

MaEtUgR
Copy link
Member

@MaEtUgR MaEtUgR commented Oct 19, 2017

The battery percentage like it is right now is unpredictable jumping around and far from accurate.

  • totally empty battery is not 0%
    also this is not really tunable because parameters do not meet invariants
  • low pass filter for battery state in there does not have time abstraction nor is it tunable
    it's dependent on execution frequency and unpredicatable
  • there's no fusion with current integrated to capacity it's just min(estimate_v, estimate_a)
  • thrust gets used to compensate voltage drop on load linearly
    but in reality this relation is not linear but rather quadratic in my experience.
  • generally known the voltage to remaining capacity function for li-po batteries is non-linear
    EDIT: While I was testing I found out that a big part of that nonlinearity comes from the load and can be corrected with the internal resisatnce model for the battery and total current measurements. So still non-linear but less severe.

EDIT: Crossed out points are moved to the next improvement step.

Let's change it, that's my take on the problem.


I noticed this pr is lacking a clear description for what it does:

  • It makes shure the parameters BAT_V_CHARGED and BAT_V_EMPTY set the voltages where the estimate using the voltage shows 100% or 0% respectively. This is achieved by correcting the voltage measurement only internally for the estimation to correct for voltage sag caused by the battery load.
  • It assumes the impact of the thrust onto the voltage is quadratic. This depends on the ESCs and sadly the thrust compensation is by far less usable/acurate than the current compensation.
  • It kicks out duplicate lowpass filtering of voltage and current.
  • It refactors to make the battery estimation more readable with more comments and clearer unit conversions.
  • If you have current measurement and battery capacity set it uses a simple fusion algorithm to incorporate voltage and capacity estimation:
    Description: On bootup it initially takes the estimate calculated from voltage. While consuming energy it directly reduces the estimate with the integrated current. The voltage estimate gets encorporated with a very strong low pass filter. The lower (emptier) the estimate produced from voltage is, the stronger it gets encorporated to avoid deep discharging in case of wrong parameters or faulty battery.

Here's an example for how it should usually work:
battery_curve2

Here's a theoretical reaction to a battery that would suddenly have a very low voltage (because it's faulty or the initial estimation was wrong or the parameters are not correct):
battery_curve_faulty
green: capacity based estimation
red: voltage based estimation
blue: resulting estimation from the fusion

@MaEtUgR MaEtUgR self-assigned this Oct 19, 2017

// remaining charge estimate based on voltage and internal resistance (drop under load)
float bat_v_empty_dynamic = _param_v_empty.get();

if (bat_r >= 0.0f) {
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Might as well use _param_r_internal.get() and _param_v_empty.get() directly.

Copy link
Member Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

_param_v_empty.get() already gets used directly now.
bat_r made it more readable in my opinion but you're right I should rename the block param to be more readable, that's better.
Thanks for already looking at it 👍

@MaEtUgR MaEtUgR force-pushed the battery-estimation branch from 2128d23 to f1c60c4 Compare October 19, 2017 19:57
@MaEtUgR MaEtUgR changed the title [WIP] Battery estimation corrections [WIP] Battery Estimation Corrections Oct 19, 2017
@Antiheavy
Copy link
Contributor

Looks like a good improvement.

In my experience steady state payload and avionics power draw can be highly significant on some platforms. I’ve worked on several fixed wing systems where it was 1/3rd of the total power draw (average propulsion being 2/3rds). Do you think a new param to account for this might be worth while?

Also, temperature is always the Achilles heel for these types of battery models.... very tough to model though since there are so many different chemistry types and battery temperature measurement isn’t common with hobby grade batteries.

@MaEtUgR
Copy link
Member Author

MaEtUgR commented Oct 23, 2017

@Antiheavy Thanks for your kind words and additional ideas. You should probaly know that while I'm interested in the topic my goal here is to first fix the obvious things. When I tried with the current implementation and default configuration in simulation with a deep discharge voltage input I still had >10% left. We don't need advanced considerations to fix that.

To your questions:

  • Not sure how this relates to the remaining capacity estimation. If you want to have a good estimate you need a current (and combined with voltage: power) measurement anyways. And if you have that the estimation should go down faster on higher power draw. The thrust compensation is only a rough help against extreme voltage fluctuations for those who don't have a current sensor because on most aircrafts the total thrust results in the highest power consumtion. Anything I misunderstood?
  • Temperature like the non-linearity of the discharge curve with constant power draw are things I would love to incorporate into the estimation. If you have any suggestions on real world mathematical approximations for those effect please share them.

@MaEtUgR MaEtUgR force-pushed the battery-estimation branch 2 times, most recently from 3e6f114 to e1df47e Compare October 23, 2017 15:07
@Antiheavy
Copy link
Contributor

sorry for the delayed response. I should have looked at the code more carefully, I see that adding a steady state avionics draw wont really help here since it isn't doing a "time remaining" estimate. I was more lamenting the fact that temperature effects are complicated and without decent temp measurement and a complicated battery math model that is chemistry specific it is hard to get super accurate with just current and voltage measurement. That is okay, what you have here is still a nice improvement.

@MaEtUgR MaEtUgR changed the title [WIP] Battery Estimation Corrections Battery Estimation Corrections Oct 29, 2017
@MaEtUgR
Copy link
Member Author

MaEtUgR commented Oct 29, 2017

The most severe but still basic problems are fixed and hence I suggest to merge this as the first take.

I think there's still potential:

  • The time abstracted filter: I was looking for a simple runtime configurable FIR filter but didn't find a suitable solution.
  • The voltage/capacity estimate fusion could still be more elaborate but the basic idea is implemented and worked very well in my tests.
  • Non-linearity would in my opinion require a lookup table but I didn't want to fix one yet because there needs to be a lot of verification. Batteries are all different and there should be a common denominator for this linearization which can only improve performance compared to assuming it's linear already.

Note for the user: After merging this pr battery percentages have a new (maybe very old) correct meaning. When configuring the battery parameters as their description states 0% means the battery is completely empty.
You can already see this in SITL where you never had less than 17% before even though the voltage of the virtual batteries went below the value you configured for empty: https://github.com/PX4/Firmware/pull/8153/files#diff-23c67e906b712051714dd61b12fce367L377

@MaEtUgR
Copy link
Member Author

MaEtUgR commented Oct 31, 2017

I rebased, added my latest enhancement and wrote a description with examples in the original post. I don't know why CI fails which is why I currently assume it's not my mistake.

I would personally not merge this before the 1.7 release.

@MaEtUgR MaEtUgR force-pushed the battery-estimation branch from 071ad3a to 9818602 Compare November 1, 2017 15:32
@MaEtUgR
Copy link
Member Author

MaEtUgR commented Nov 1, 2017

I rebased and adjusted the weight for the voltage estimate just a little bit such that it really results like shown in the plot with the simulated faulty battery that suddenly drops the voltage, now it's according to my tests on the safe side.

Can someone else please test? Otherwise I would say it's ready to merge (still assuming CI is globally broken).

…ling preflight checks to take off again

also added comments and removed throttle compensation because there is no real battery emulation with load drop
@MaEtUgR MaEtUgR force-pushed the battery-estimation branch from 9818602 to 0ad73ea Compare January 4, 2018 10:33
@MaEtUgR
Copy link
Member Author

MaEtUgR commented Jan 4, 2018

I rebased again to make it compatible with the changes here: 202c291#diff-23c67e906b712051714dd61b12fce367

I added the last commit to make sure SITL users can fly as musch as they want and ar not restricted from taking off again after one virtual battery is empty.

@MaEtUgR MaEtUgR added this to the Release v1.8.0 milestone Jan 4, 2018
@ChristophTobler ChristophTobler merged commit 385212f into master Jan 11, 2018
@ChristophTobler ChristophTobler deleted the battery-estimation branch January 11, 2018 07:36
@ndepal
Copy link
Contributor

ndepal commented Jan 12, 2018

After updating to master today I am having problems with battery estimation on a PixRacer. It keeps reporting critically low battery after seconds of flight and I had to enable the power circuit breaker to be able to take off more than once per boot.

Could this PR be the cause of this @MaEtUgR ?

I have not changed any parameters after updating. The parameters for number of cells, full and empty voltage, voltage divider and load drop are configured. All other values are untouched.

I also failed to find PX4 specific battery estimator configuration documentation. All I found was the QGC doc page, which doesn't state much more than QGC itself.
Are there specific instructions to be followed to get this working right?

@MaEtUgR
Copy link
Member Author

MaEtUgR commented Jan 12, 2018

@ndepal Thanks for your report, sorry to hear that. The cause is likely this PR. That said I'm pretty sure it depends on the used parameters because we have a lot of multicopter flight hours on the pr. The only thing that's supposed to change is the scaling of the parameters in a way that the parameters really do exactly as their description says.

I'll double check the default parameters and come up with some documentation, that's pretty important. Can you send me a log of the case in which you wasn't satisfied? Then I could track it down and help you more easily.

@LorenzMeier
Copy link
Member

@PX4/testflights Could you please comment on wether you found issues in today's master test flights?

@r0gelion
Copy link
Contributor

@LorenzMeier

We are seeing a drop in voltage after taking off from 100% to 80% and to 70% after 1:30 minutes of flight, this didn't happen before.

Here is a video of that behavior.

@LorenzMeier
Copy link
Member

@MaEtUgR Could you look into this? If we can't fix this quickly we need to roll back the changes.

@MaEtUgR
Copy link
Member Author

MaEtUgR commented Jan 16, 2018

@r0gelion The video shows the problem very directly, do you have the log of this or a similar flight? It would help me to identify the problem without having to try all combination of parameters in hope to be able to reproduce.

@r0gelion
Copy link
Contributor

Here is a similar flight with the problem.
https://review.px4.io/plot_app?log=1dffb068-95fb-427c-9b3f-eba9ab6b9052

The autopilot used is a Pixhawk 3 Pro, but also happens with Pixhawk 1 and Pixhawk mini

@MaEtUgR
Copy link
Member Author

MaEtUgR commented Jan 16, 2018

  • @r0gelion both in your log and in the one @santiago3dr sent me (https://review.px4.io/plot_app?log=2a23cbbc-5e32-4659-b9c4-724a6106f212) the parameter BAT_V_CHARGED is different from default namely 4.15V instead of 4.05V. If you would reset it and continue to use the vehicle without using current measurements (default) you wouldn't have such a big percentage jump in the beginning of your flight anymore.
  • You could use the current measurement of your vehicle to correct the voltage for the load and get a better estimation, I'll add that to the documentation.
  • The power supply check which reportedly failed with the Intel aero is a different problem and according to my assumption about intitialization where the battery estimate is probably 0% at the beginning and because the logic makes low battery states irreversible https://github.com/PX4/Firmware/blob/master/src/modules/systemlib/battery.cpp#L210-L224 it will not allow any flight even if the estimate is 100% just afterwards... I'll look at initialization and also reversability of low battery states. Sometimes it just does not make sense e.g. switching the battery without repowering the autopilot would probably lead to the same problem.

@r0gelion
Copy link
Contributor

r0gelion commented Jan 19, 2018

@MaEtUgR
We reset the BAT_V_CHARGED parameter and the problem was fixed. Thank you!

@hamishwillee
Copy link
Contributor

@MaEtUgR

You could use the current measurement of your vehicle to correct the voltage for the load and get a better estimation, I'll add that to the documentation.

Did this get added? Can you minimally please create a doc issue and link here.

@MaEtUgR
Copy link
Member Author

MaEtUgR commented Jan 30, 2018

@hamishwillee It's linked above because I cross referenced, you found it: PX4/PX4-user_guide#131

@hamishwillee
Copy link
Contributor

Cheers! I did this one much earlier :-)

@pietrodn
Copy link
Contributor

pietrodn commented Jun 6, 2018

The voltage correction (battery.cpp, L175) is wrong: the current_a needs to be divided by the number of cells too. This gives incorrect battery estimates in some cases.
I will post another PR to correct that.

@MaEtUgR
Copy link
Member Author

MaEtUgR commented Jun 19, 2018

@pietrodn The original implementation from this pr was wrong because I overlooked the internal resistance parameter to be defined per cell and not per battery. See the fix here: https://github.com/PX4/Firmware/pull/8868/files

After that I currently don't see how it should be still wrong. Deviding the current by the number of cells does theoretically not make sense because the full current has to flow through every cell.

If that's not what you mean could you please explain in more detail?

@pietrodn
Copy link
Contributor

Moments after posting the previous comment, I realized I was just plain wrong.
I thought I had deleted it, but that was not the case. Sorry!

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

Successfully merging this pull request may close these issues.

9 participants