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 critical/low actions #7213

Merged
merged 15 commits into from Mar 27, 2018

Conversation

WickedShell
Copy link
Contributor

This builds upon #7177 to enable different failsafe levels per connected battery, as well as allowing the vehicle to define a critical and a low battery action. This also serves as a replacement for #5000.

This is a WIP at the moment as this has only touched plane so far. Given the scope of the changes, and how it touches all the vehicles I'd like to get feedback on the proposed approach before I look at reworking copter/rover/sub to all support this as well. (I don't really know what the best actions are for a lot of those vehicles, although I think that some like terminate can be supported on all vehicles if AFS is enabled. (The initial pr would probably just present the options to have the current behavior on those vehicles unless someone wants to steer further).

A couple of points worth noting here at a top leve that I would appreciate feedback onl:

  1. As I've presented it right now both critical and low battery actions use the same timeout duration to trip based on battery voltage, (they are both referencing the BATT_LOW_TIMER parameter). I can't see a strong reason why you would want a different timeout for critical vs long, and would prefer to rename this as BATT_FS_TIMER but it would be yet another param rename. Having 2 timers is easy, but I'm not sure its worth the param space.
  2. I left the FS actions in the vehicle library to determine what to do on low battery. If we had the documentation changes PR that allows us to tag a param doc as vehicle specific then we could move this parameter into the AP_BattMonitor level.

Copy link
Contributor

@amilcarlucas amilcarlucas left a comment

Choose a reason for hiding this comment

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

Thanks Michael. I think this stuff adds important functionality that benefits people doing long range flights.

I do see a couple of PRs that potentially conflict with this one. getting this one in will probably simplify those other PRs. This needs a rebase though.

I think we now have vehicle specific docs, so some of this can be moved to the library, and all vehicles benefit from it :)

What is terminate action ???

AP_Float _curr_amp_per_volt; /// voltage on current pin multiplied by this to calculate current in amps
AP_Float _curr_amp_offset; /// offset voltage that is subtracted from current pin before conversion to amps
AP_Int32 _pack_capacity; /// battery pack capacity less reserve in mAh
AP_Int16 _watt_max; /// max battery power allowed. Reduce max throttle to reduce current to satisfy t his limit
Copy link
Contributor

Choose a reason for hiding this comment

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

whitespaces in comment

@amilcarlucas
Copy link
Contributor

#7432 provides a way to customize what happens when a FS gets triggered. So these two can get combined ?

@WickedShell WickedShell force-pushed the wickedshell/batt-failsafes branch 3 times, most recently from 6634324 to 753b523 Compare March 1, 2018 23:04
float voltage_resting_estimate; // voltage with sag removed based on current and resistance estimate
float resistance; // resistance calculated by comparing resting voltage vs in flight voltage
bool healthy; // battery monitor is communicating correctly
cells cell_voltages; // battery cell voltages in millivolts, 10 cells matches the MAVLink spec
Copy link
Contributor

Choose a reason for hiding this comment

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

Does the added value of indentation surpass the value of breaking git blame ?

Copy link
Contributor Author

Choose a reason for hiding this comment

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

I've been caught! :)

@WickedShell
Copy link
Contributor Author

@amilcarlucas I'd hold off on reviewing to much yet, been pushing more for linking to others :) Moving a large pile of additional stuff into AP_BattMonitor first.

@WickedShell WickedShell force-pushed the wickedshell/batt-failsafes branch 3 times, most recently from bbd8e97 to 1c4b3dc Compare March 2, 2018 03:39
@WickedShell
Copy link
Contributor Author

WickedShell commented Mar 2, 2018

This has been pushed with support for all vehicles (Tracker is a no op at the moment, but the skeleton is there for others).

Summary of changes:

  • Compass current compensation is automatically polled from the battery if needed, and is now consistent across all vehicles
  • All vehicles skip running fail safes while disarmed based on soft armed. (Sub and Copter were basing it on motors->armed())
  • Copter special case for USB disabling failsafes has been removed
  • Copter will now trigger failsafes during motor test and compass motor cal. This behavior can be restored to what it was, but the rational for running failsafes during this is to let someone know if they are risking damaging a battery, and in the cal step running at an out of range battery voltage seems like it could produce different results. This needs a copter expert to review (particularly to make sure the copter can't accidentally takeoff if it failsafes during a motor test).
  • All vehicles now have a low and critical threshold set per battery, with a selectable set of actions for both low and critical (again per battery). This allows you to select a different failsafe action for your propulsion battery and avionics battery.
  • Sub no longer broadcasts a statustext every 20 seconds about low battery
  • Sub now has a param conversion table for the first time
  • Rover and tracker both report the battery in SYS_STATUS the same way copter/plane do. (Always present, enabled when there is an instance loaded, unhealthy if a failsafe occurs).
  • Removes the Battery example, as it was constantly being broken, and was causing me headaches to maintain it

Outstanding Issues:

  • Needs a form of failsafe priorities. At the moment it assumes that each increasing failsafe action parameter value is of higher importance then the previous. While this works well on plane at the moment it doesn't scale if we insert something of middle priority, and it doesn't work for Copter/Sub at all at the moment. The two solutions for this are to either break the param conversion code (which while I think it's valid it's probably not popular), or to pass a table that maps failsafe actions to priority levels. (This is probably the best bet, but I wanted to source other opinions before I did it).

Needed Testing (SITL is fine):

  • Copter
  • Plane
  • Sub
  • Rover
  • Pram conversion

If the vehicle maintainers can chime in at this point that would be great!

@WickedShell WickedShell force-pushed the wickedshell/batt-failsafes branch 3 times, most recently from f3bb10b to 8673019 Compare March 2, 2018 05:03
@WickedShell
Copy link
Contributor Author

Pushed the nitpick fixes already. Your list looks correct to me.

To be fair I was actually expecting some of the motor current limiting stuff to work already on quadplane since I could see the parameters, but I'm glad I wasn't banking on it.

@khancyr
Copy link
Contributor

khancyr commented Mar 21, 2018

checking that the param conversion is working !

@WickedShell
Copy link
Contributor Author

@khancyr Great, thanks!

After chatting with tridge the main risk with battery compensation was that quadplanes could use the forward battery rather then the vertical battery, which wouldn't help, and the other concern is if you have a single battery during transition. I've pushed an additional commit that allows AP_Motors to specify what battery index is used (which is primarily useful for multi battery setups), and the default value won't change behavior for anyone.

The other change there is that AP_MotorsMulticopter::update_lift_max_from_batt_voltage() now uses the resting voltage as part of the check rather then the battery voltage. This was checked with Leonard first and it makes more sense to be checking the value we will be using in compensation rather then a different one.

Copy link
Contributor

@rmackay9 rmackay9 left a comment

Choose a reason for hiding this comment

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

seems OK to me. I tested compassmot (as requested by @WickedShell) and it seems to produce similar values to what master produces.

before-after

@WickedShell
Copy link
Contributor Author

@rmackay9 the main concern was if you could trigger a battery failsafe that actually caused the vehicle to try and do something during the compassmot procedure.

@rmackay9
Copy link
Contributor

@WickedShell, I tested attempting to trigger a radio failsafe during the compassmot procedure but wasn't able to. In particular I did this:

  • First ensured that the rc failsafe was working by switching to loiter mode, taking-off (by raising throttle) then turned off the radio. the RC failsafe correct switched to Land mode (because the vehicle was very near home).
  • armed the vehicle but remained landed and tried to start compassmot procedure, it would not start.
  • left the vehicle disarmed, started the compassmot procedure and turned off the radio, no failsafe was triggered. The EKF was very unhappy but I think that's probably because of timing.

@WickedShell
Copy link
Contributor Author

@rmackay9 right, that's not the same thing unfortunately. The old code used to explicitly disable the battery failsafes by changing the parameter values. That was removed in this version, however if we need to reintroduce a disable for the cal that's fine, but the modification of parameters was a bad way to do it.

@rmackay9
Copy link
Contributor

One small thing is the default BATT_LOW_VOLT is too high. It shows up as "11" on my IRIS anyway but the default previously was lower (10.4 maybe?).

By the way, i also tried triggering a battery failsafe during compass mot but wasn't able to.

@WickedShell
Copy link
Contributor Author

@rmackay9 ah good catch, not sure where I pulled 11V from. Updated. Great to hear that the failsafes aren't an issue while doing the test.

Assuming @OXINARF and others are good, I think this is good.

// @Param: BAT_IDX
// @DisplayName: Battery compensation index
// @Description: Which battery monitor should be used for doing compensation
// @Range: 0 1
Copy link
Member

Choose a reason for hiding this comment

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

Should this be values instead of range? If you want to go with range, then add the @Increment: 1.

@OXINARF OXINARF merged commit 050b8eb into ArduPilot:master Mar 27, 2018
@OXINARF
Copy link
Member

OXINARF commented Mar 27, 2018

Merged, thanks!

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

Successfully merging this pull request may close these issues.

None yet

7 participants