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

Consider the throttle load for battery voltage calculation #1211

Merged
merged 14 commits into from
Jul 21, 2014
Merged

Conversation

LorenzMeier
Copy link
Member

@DrTon @sjwilks This change considers the internal resistance of the batteries for charge calculation.

@DrTon I'm aware of your capacity PR and want to integrate it as well. However, while this change allows us to get closer to the lower limit (and hence warn at the right time) the charge based approach (without a smart battery) requires still a voltage based sanity check/limit.

So while this PR does not improve accuracy, it helps to not warn the user too soon because of high throttle events.

@@ -56,7 +56,7 @@ PARAM_DEFINE_FLOAT(TRIM_YAW, 0.0f);
*
* @group Battery Calibration
*/
PARAM_DEFINE_FLOAT(BAT_V_EMPTY, 3.4f);
PARAM_DEFINE_FLOAT(BAT_V_EMPTY, 3.3f);
Copy link
Member Author

Choose a reason for hiding this comment

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

3.4V was definitely too high. 3.3V is better, but might still be a bit high. We could consider going to 3.25 or 3.2 (note that with default params under load empty == 3.2 - 0.1V then).

Copy link
Contributor

Choose a reason for hiding this comment

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

After 3.4V voltage drops much faster and deep discharge (3.2 is deep enough!) is very bad for battery health. Default parameters should be tuned for safe flight. With 3.2V copter may crash after 3 seconds after first warning if user forgot to charge battery, it may be not enough to land.

Of course it depends on battery model, but I would like to stay on safe side with 3.4V. If user wants to kill the battery, he can change parameter.

The problem with voltage drops on high thrust should be solved by internal resistance compensation I think, that you are already trying to do.

Copy link
Member Author

Choose a reason for hiding this comment

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

Ok, convinced - I'll change this back.

@DrTon
Copy link
Contributor

DrTon commented Jul 19, 2014

Why not to use current and battery resistance instead of thrust (that strictly is incorrect at all, because of limiting in mixer)?

@LorenzMeier
Copy link
Member Author

The internal resistance is a function of the current, which is correlated to trust. Since there are no specs available for those batteries taking the observed voltage drop from flight logs is the most accurate guess we have.

@DrTon
Copy link
Contributor

DrTon commented Jul 19, 2014

I thought that we assuming internal resistance constant... :)

@LorenzMeier
Copy link
Member Author

@DrTon I have to think a bit more about what to prefer as a model. All I know right now is that the voltage drop can be read off a log file quite easily for a given setup and its a simple number for users to enter.
Since we do not know the internal resistance of a pack we would anyway have to convert current and drop back to resistance 8).

@LorenzMeier
Copy link
Member Author

And yes, current would be more accurate. The problem is that the current sensor right now is not very useful for all setups, as it has huge offsets. Not a problem for a quad drawing 16 amps, but a plane just drawing 4-8A peak is easily off (because the sensor has a ~4A offset). The commanded throttle is a probably a more stable estimate, although it will have indeed some error.

There is another factor I like about it: It leads the current. So when applying the voltage scaling the voltage has not yet dropped, not creating a false alarm. If we go for current, we might have a drop before the correct scaling has been applied.

But I think this needs more testing and log file analysis. This current simple approach will however for sure improve the response for most setups without overcomplicating things.

@LorenzMeier
Copy link
Member Author

@sjwilks This would also be a flight testing candidate.

@DrTon
Copy link
Contributor

DrTon commented Jul 19, 2014

~4A offset is too much, I never had such big values.

What about internal resistance - it depends not only on battery model, but also on temerature significantly. It would be good to do estimation for it, need to think how to do this.

@LorenzMeier
Copy link
Member Author

Here is a dataset from a test with full throttle - note that the charging estimate only varies slightly thanks to the compensation:

ms  batt %  current voltage (in mV, 2S pack)
2092    96  0   8337
3226    96  0   8342
4020    95  0   8333
5038    96  0   8342
6082    96  0   8337
7008    96  0   8337
8033    96  0   8337
9186    96  0   8342
9993    96  0   8342
11030   96  0   8342
12004   95  0   8333
13010   96  0   8333
14025   97  0   8329
15056   97  0   8325
16027   96  0   8230
17012   94  0   8180
18028   95  0   8234
19056   94  0   8306
20057   94  0   8311
21038   94  0   8315
22084   94  0   8315
23033   95  0   8325
24015   95  0   8325
25031   95  0   8325
26070   95  0   8325
27000   95  0   8325
28033   95  0   8325
29119   95  0   8329
29991   95  0   8325
31025   95  0   8329
31998   95  0   8325
33010   95  0   8325
34018   95  0   8329
35048   95  0   8325
36159   95  0   8325
36995   95  0   8325
38016   95  0   8329
39056   95  0   8325

@LorenzMeier
Copy link
Member Author

@sjwilks I fixed the IO voltage estimate over lunch break based on a dataset I captured during the weekend. I would appreciate if you could validate this. It should now read the same voltage as your lab supply.

@LorenzMeier
Copy link
Member Author

After more meticulous testing I went for the theoretical voltage divider values, which is actually the best we can do. This should now be fairly accurate and outperform the simpler voltage measurement devices (e.g. in standard power supplies).

Merging. Yay!

LorenzMeier added a commit that referenced this pull request Jul 21, 2014
Consider the throttle load for battery voltage calculation
@LorenzMeier LorenzMeier merged commit 5bb3e92 into master Jul 21, 2014
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.

2 participants