» S
h
o
w
 
M
e
n
u
» S
h
o
w
 
M
e
n
u
Page Content

Profiling battery discharge

AutoQuad has a facility to estimate the State of Charge (SoC) of the flight battery in real time.  The SoC value is not presently used by any functions; however it is displayed in the GCS’ HUD.   In the future, it could be used to determine remaining flight time or if there is enough battery charge to complete a mission plan.

In order to determine the SoC, the flight battery’s discharge curve has to be profiled.
The default curve will not match yours.

With a fully charged battery pack and SD card logging enabled, lift off and maintain a smooth hover to the lowest pack voltage you would normally fly to.  If your PositionHold is well setup, you can use that to maintain hover.  Pick a windless day and stay out of ground effect.
After the flight, take a look at the log to verify that you achieved fairly linear motor output and smooth battery discharge.

Example: 
Linear motor output overall.  There was some breeze during this flight.

Battery voltage curve during the flight.  The idea is to place a constant flight load on the pack to achieve a smooth discharge.

‘batCal’ – the battery profiler utility is located within the /ground directory of the AutoQuad source package.  It is currently only available as source code.  You will have to compile it yourself.  Under Linux, you might have to install a few dev libraries for it to compile successfully.

Run ‘batCal’ with your hover log file as a parameter.  If you want to use a higher voltage value than the end voltage of the flight as the zero SoC, you provide that as an additional ‘–zero=value‘ command line parameter.

Answer the prompts and ‘batCal’ will come up with a curve function for the pack’s discharge profile.  The displayed SPVR_BAT_CRV values can now be used for that battery pack.  Modify the onboard parameters within the SPVR section and save to ROM.

Naturally, if you fly with packs of different characteristics or age, they must be profiled individually and then modify onboard parameters when flying with that pack.  If you change significant parts of your system, such as weight or props; you should re-profile.

If you told batCal to generate a plot, it might look something like this.

AQ uses the parameters to build a lookup table to determine the SoC (100% – 0%) based on the pack voltage.

If desired, you can modify the code to transmit the SoC via MAVLink.

In aq_mavlink.c, change:

mavlink_msg_sys_status_send(MAVLINK_COMM_0, 0, 0, 0, 1000-mavlinkData.idlePercent, adcData.vIn * 1000, -1, (adcData.vIn - 9.8f) / 12.6f * 1000, 0, mavlinkData.packetDrops, 0, 0, 0, 0);

to

mavlink_msg_sys_status_send(MAVLINK_COMM_0, 0, 0, 0, 1000-mavlinkData.idlePercent, adcData.vIn * 1000, -1, (int)supervisorData.soc, 0, mavlinkData.packetDrops, 0, 0, 0, 0);

QGCS will then show the SoC (battery_remaining as a percentage)

This page was created on 4-Oct-12 by gofaster. Last modified on 19-Aug-14 by kinderkram.